From 8b87d19d3e4f768235cb636565d3597c6cf32c3a Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 14:11:30 -0500 Subject: [PATCH 1/8] Made GPS example, clean up some printing --- examples/gps.rs | 123 +++++++++++++++++++++++++++ src/containers/symbol.rs | 4 +- src/linalg/mod.rs | 1 + src/rerun.rs | 9 ++ src/residuals/between.rs | 20 +---- src/residuals/imu_preint/residual.rs | 12 +-- src/residuals/prior.rs | 24 +----- src/residuals/traits.rs | 4 +- src/variables/se2.rs | 8 +- src/variables/so2.rs | 12 ++- 10 files changed, 158 insertions(+), 59 deletions(-) create mode 100644 examples/gps.rs diff --git a/examples/gps.rs b/examples/gps.rs new file mode 100644 index 0000000..17e2029 --- /dev/null +++ b/examples/gps.rs @@ -0,0 +1,123 @@ +/* +This is a port of the "LocalizationExample.cpp" found in the gtsam repository +https://github.com/borglab/gtsam/blob/11142b08fc842f1fb79ccf3017946d70f5173335/examples/LocalizationExample.cpp + +A simple 2D pose slam example with "GPS" measurements + - The robot moves forward 2 meter each iteration + - The robot initially faces along the X axis (horizontal, to the right in 2D) + - We have full odometry between pose + - We have "GPS-like" measurements implemented with a custom factor +*/ + +#![allow(unused_imports)] +use factrs::{ + assign_symbols, + containers::{Graph, Values}, + dtype, fac, + linalg::{Const, ForwardProp, Numeric, NumericalDiff, VectorX}, + noise::GaussianNoise, + optimizers::GaussNewton, + residuals::{BetweenResidual, Residual1}, + traits::{GraphOptimizer, Optimizer, Variable}, +}; + +// Our state will be represented by SE2 -> theta, x, y +// VectorVar2 is a newtype around Vector2 for optimization purposes +use factrs::variables::{VectorVar2, SE2}; + +#[derive(Clone, Debug)] +pub struct GpsResidual { + meas: VectorVar2, +} + +impl GpsResidual { + pub fn new(x: dtype, y: dtype) -> Self { + Self { + meas: VectorVar2::new(x, y), + } + } +} + +// The `mark` macro handles serialization stuff and some custom impl as well +#[factrs::mark] +impl Residual1 for GpsResidual { + // Use forward propagation for differentiation + type Differ = ForwardProp<::DimIn>; + // Alternatively, could use numerical differentiation (6 => 10^-6 as denominator) + // type Differ = NumericalDiff<6>; + + // The input variable type, input dimension of variable(s), and output dimension of residual + type V1 = SE2; + type DimIn = Const<3>; + type DimOut = Const<2>; + + // D is a custom numeric type that can be leveraged for autodiff + fn residual1(&self, v: SE2) -> VectorX { + // Convert measurement from dtype to T + let p_meas = VectorVar2::::dual_convert(&self.meas); + // Convert p to VectorVar2 as well + let p = VectorVar2::from(v.xy().into_owned()); + + p.ominus(&p_meas) + } + + // You can also hand-code the jacobian by hand if extra efficiency is desired. + // fn residual1_jacobian(&self, values: &Values, keys: &[Key]) -> DiffResult { + // let p: &SE2 = values + // .get_unchecked(keys[0]) + // .expect("got wrong variable type"); + // let s = p.theta().sin(); + // let c = p.theta().cos(); + // let diff = MatrixX::from_row_slice(2, 3, &[0.0, c, -s, 0.0, s, c]); + // DiffResult { + // value: self.residual1(p.clone()), + // diff, + // } + // } + // As a note - the above jacobian is only valid if running with the "left" feature disabled + // Switching to the left feature will change the jacobian used +} + +// Here we assign X to always represent SE2 variables +// We'll get a compile-time error if we try anything else +assign_symbols!(X: SE2); + +fn main() { + let mut graph = Graph::new(); + + // Add odometry factors + let noise = GaussianNoise::<3>::from_diag_covs(0.1, 0.2, 0.2); + let res = BetweenResidual::new(SE2::new(0.0, 2.0, 0.0)); + let odometry_01 = fac![res.clone(), (X(0), X(1)), noise.clone()]; + let odometry_12 = fac![res, (X(1), X(2)), noise]; + graph.add_factor(odometry_01); + graph.add_factor(odometry_12); + + // Add gps factors + let g0 = fac![GpsResidual::new(0.0, 0.0), X(0), 1.0 as std]; + let g1 = fac![GpsResidual::new(0.0, 2.0), X(1), 1.0 as std]; + let g2 = fac![GpsResidual::new(0.0, 4.0), X(2), 1.0 as std]; + graph.add_factor(g0); + graph.add_factor(g1); + graph.add_factor(g2); + + // Make values + let mut values = Values::new(); + values.insert(X(0), SE2::new(1.0, 2.0, 3.0)); + values.insert(X(1), SE2::identity()); + values.insert(X(2), SE2::identity()); + + // These will all compile-time error + // values.insert(X(5), VectorVar2::identity()); // wrong variable type + // let f = fac![GpsResidual::new(0.0, 0.0), (X(0), X(1))]; // wrong number of keys + // let n = GaussianNoise::<5>::from_scalar_sigma(0.1); + // let f = fac![GpsResidual::new(0.0, 0.0), X(0), n]; // wrong noise-model dimension + // assign_symbols!(Y : VectorVar2); + // let f = fac![GpsResidual::new(0.0, 0.0), Y(0), 0.1 as std]; // wrong variable type + + // optimize + let mut opt: GaussNewton = GaussNewton::new(graph); + let result = opt.optimize(values).expect("Optimization failed"); + + println!("Final Result: {:#?}", result); +} diff --git a/src/containers/symbol.rs b/src/containers/symbol.rs index d34a6dc..124e0eb 100644 --- a/src/containers/symbol.rs +++ b/src/containers/symbol.rs @@ -27,7 +27,7 @@ pub struct Key(pub u64); impl Symbol for Key {} -/// This provides a custom conversion two and from a u64 key. +/// This provides a custom conversion to and from a u64 key. pub trait Symbol: fmt::Debug + Into {} pub struct DefaultSymbol { @@ -59,7 +59,7 @@ impl From for Key { impl fmt::Debug for DefaultSymbol { fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "({}, {})", self.chr, self.idx) + write!(f, "{}{}", self.chr, self.idx) } } diff --git a/src/linalg/mod.rs b/src/linalg/mod.rs index 3433edd..d503eb2 100644 --- a/src/linalg/mod.rs +++ b/src/linalg/mod.rs @@ -65,6 +65,7 @@ use paste::paste; use crate::variables::Variable; /// A struct to hold the result of a differentiation operation +#[derive(Debug, Clone)] pub struct DiffResult { pub value: V, pub diff: G, diff --git a/src/rerun.rs b/src/rerun.rs index 4731a55..7480ec3 100644 --- a/src/rerun.rs +++ b/src/rerun.rs @@ -32,6 +32,7 @@ SE3 -> Arrows3D, Points3D // ------------------------- 2D Objects ------------------------- // // 2D Vectors +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a VectorVar2> for Vec2D { fn from(v: &'a VectorVar2) -> Vec2D { Vec2D::new(v[0] as f32, v[1] as f32) @@ -58,6 +59,7 @@ impl From for Points2D { } // 2D Rotations +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SO2> for Arrows2D { fn from(so2: &'a SO2) -> Arrows2D { let mat = so2.to_matrix().map(|x| x as f32); @@ -82,6 +84,7 @@ impl From for Arrows2D { } // 2D SE2 +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SE2> for Arrows2D { fn from(se2: &'a SE2) -> Arrows2D { let xy: [f32; 2] = se2 @@ -101,6 +104,7 @@ impl From for Arrows2D { } } +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SE2> for Points2D { fn from(se2: &'a SE2) -> Points2D { let xy = [se2.x() as f32, se2.y() as f32]; @@ -114,6 +118,7 @@ impl From for Points2D { } } +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SE2> for Vec2D { fn from(se2: &'a SE2) -> Vec2D { let xy = [se2.x() as f32, se2.y() as f32]; @@ -129,6 +134,7 @@ impl From for Vec2D { // ------------------------- 3D Objects ------------------------- // // 3D Vectors +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a VectorVar3> for Vec3D { fn from(v: &'a VectorVar3) -> Vec3D { Vec3D::new(v[0] as f32, v[1] as f32, v[2] as f32) @@ -155,6 +161,7 @@ impl From for Points3D { } // 3D Rotations +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SO3> for Rotation3D { fn from(so3: &'a SO3) -> Rotation3D { let xyzw = [ @@ -173,6 +180,7 @@ impl From for Rotation3D { } } +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SO3> for Arrows3D { fn from(so3: &'a SO3) -> Arrows3D { let mat = so3.to_matrix().map(|x| x as f32); @@ -217,6 +225,7 @@ impl From for Transform3D { } } +#[allow(clippy::unnecessary_cast)] impl<'a> From<&'a SE3> for Arrows3D { fn from(se3: &'a SE3) -> Arrows3D { let arrows: Arrows3D = se3.rot().into(); diff --git a/src/residuals/between.rs b/src/residuals/between.rs index 89f657a..a0b50b2 100644 --- a/src/residuals/between.rs +++ b/src/residuals/between.rs @@ -1,19 +1,11 @@ -use core::fmt; - use nalgebra::{DimNameAdd, DimNameSum}; -use super::Residual2; -#[allow(unused_imports)] use crate::{ - containers::{Key, Values}, linalg::{ - AllocatorBuffer, Const, DefaultAllocator, DiffResult, DimName, DualAllocator, DualVector, - ForwardProp, MatrixX, Numeric, VectorX, - }, - variables::{ - Variable, VariableUmbrella, VectorVar1, VectorVar2, VectorVar3, VectorVar4, VectorVar5, - VectorVar6, SE2, SE3, SO2, SO3, + AllocatorBuffer, DefaultAllocator, DualAllocator, DualVector, ForwardProp, Numeric, VectorX, }, + residuals::Residual2, + variables::{Variable, VariableUmbrella}, }; /// Binary factor between variables. @@ -57,9 +49,3 @@ where v1.compose(&delta).ominus(&v2) } } - -impl fmt::Display for BetweenResidual

{ - fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "{:?}", self) - } -} diff --git a/src/residuals/imu_preint/residual.rs b/src/residuals/imu_preint/residual.rs index f1ffa41..c7fd27f 100644 --- a/src/residuals/imu_preint/residual.rs +++ b/src/residuals/imu_preint/residual.rs @@ -1,12 +1,8 @@ -use std::fmt; - -use nalgebra::Const; - use super::{delta::ImuDelta, Accel, Gravity, Gyro, ImuState}; use crate::{ containers::{Factor, FactorBuilder, Symbol, TypedSymbol}, dtype, - linalg::{ForwardProp, Matrix, Matrix3, VectorX}, + linalg::{Const, ForwardProp, Matrix, Matrix3, VectorX}, noise::GaussianNoise, residuals::Residual6, traits::*, @@ -352,12 +348,6 @@ impl Residual6 for ImuPreintegrationResidual { } } -impl fmt::Display for ImuPreintegrationResidual { - fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "ImuPreintegrationResidual({})", self.delta) - } -} - #[cfg(test)] mod test { use crate::{ diff --git a/src/residuals/prior.rs b/src/residuals/prior.rs index 4ecf92c..23d6f7f 100644 --- a/src/residuals/prior.rs +++ b/src/residuals/prior.rs @@ -1,17 +1,9 @@ -use core::fmt; - -use super::Residual1; -#[allow(unused_imports)] use crate::{ - containers::{Key, Values}, linalg::{ - AllocatorBuffer, Const, DefaultAllocator, DiffResult, DimName, DualAllocator, DualVector, - ForwardProp, MatrixX, Numeric, VectorX, - }, - variables::{ - Variable, VariableUmbrella, VectorVar1, VectorVar2, VectorVar3, VectorVar4, VectorVar5, - VectorVar6, SE2, SE3, SO2, SO3, + AllocatorBuffer, DefaultAllocator, DualAllocator, DualVector, ForwardProp, Numeric, VectorX, }, + residuals::Residual1, + variables::{Variable, VariableUmbrella}, }; /// Unary factor for a prior on a variable. @@ -51,12 +43,6 @@ where } } -impl fmt::Display for PriorResidual

{ - fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "{:?}", self) - } -} - #[cfg(test)] mod test { @@ -64,9 +50,7 @@ mod test { use super::*; use crate::{ - linalg::{vectorx, DefaultAllocator, Diff, DualAllocator, NumericalDiff}, - symbols::X, - variables::{VectorVar3, SE3, SO3}, + containers::Values, linalg::{vectorx, DefaultAllocator, Diff, DualAllocator, NumericalDiff}, symbols::X, variables::{VectorVar3, SE3, SO3} }; #[cfg(not(feature = "f32"))] diff --git a/src/residuals/traits.rs b/src/residuals/traits.rs index fed0c66..b08260a 100644 --- a/src/residuals/traits.rs +++ b/src/residuals/traits.rs @@ -1,4 +1,4 @@ -use std::fmt::{Debug, Display}; +use std::fmt::Debug; use crate::{ containers::{Key, Values}, @@ -15,7 +15,7 @@ type Alias = ::Alias; /// one of the numbered residuals traits instead, and then call the /// [impl_residual](crate::impl_residual) macro to implement this trait. #[cfg_attr(feature = "serde", typetag::serde(tag = "tag"))] -pub trait Residual: Debug + Display { +pub trait Residual: Debug { fn dim_in(&self) -> usize; fn dim_out(&self) -> usize; diff --git a/src/variables/se2.rs b/src/variables/se2.rs index 444aa04..31da5ea 100644 --- a/src/variables/se2.rs +++ b/src/variables/se2.rs @@ -235,10 +235,8 @@ impl fmt::Display for SE2 { fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { write!( f, - "SE2({:.3}, {:.3}, {:.3})", - self.rot.log()[0], - self.xy[0], - self.xy[1] + "{}, x: {:.3}, y: {:.3}", + self.rot, self.xy[0], self.xy[1] ) } } @@ -247,7 +245,7 @@ impl fmt::Debug for SE2 { fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { write!( f, - "SE2({:?}, x: {:.3}, y: {:.3})", + "SE2({}, x: {:.3}, y: {:.3})", self.rot, self.xy[0], self.xy[1] ) } diff --git a/src/variables/so2.rs b/src/variables/so2.rs index cdd3a55..e61c2ed 100644 --- a/src/variables/so2.rs +++ b/src/variables/so2.rs @@ -152,13 +152,21 @@ impl ops::Mul for &SO2 { impl fmt::Display for SO2 { fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "SO2({:.3})", self.log()[0]) + if f.alternate() { + write!(f, "a: {:.3}, b: {:.3}", self.a, self.b) + } else { + write!(f, "theta: {:.3}", self.log()[0]) + } } } impl fmt::Debug for SO2 { fn fmt(&self, f: &mut fmt::Formatter) -> fmt::Result { - write!(f, "SO2(a: {:.3}, b: {:.3})", self.a, self.b) + if f.alternate() { + write!(f, "SO2(a: {:.3}, b: {:.3})", self.a, self.b) + } else { + write!(f, "SO2(theta: {:.3})", self.log()[0]) + } } } From 6048b57c87c62bfadd83d219714dee97846168fe Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 14:31:25 -0500 Subject: [PATCH 2/8] Typo in gps example --- examples/gps.rs | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/gps.rs b/examples/gps.rs index 17e2029..97222da 100644 --- a/examples/gps.rs +++ b/examples/gps.rs @@ -95,8 +95,8 @@ fn main() { // Add gps factors let g0 = fac![GpsResidual::new(0.0, 0.0), X(0), 1.0 as std]; - let g1 = fac![GpsResidual::new(0.0, 2.0), X(1), 1.0 as std]; - let g2 = fac![GpsResidual::new(0.0, 4.0), X(2), 1.0 as std]; + let g1 = fac![GpsResidual::new(2.0, 0.0), X(1), 1.0 as std]; + let g2 = fac![GpsResidual::new(4.0, 0.0), X(2), 1.0 as std]; graph.add_factor(g0); graph.add_factor(g1); graph.add_factor(g2); From bc44e479c362f5832ebcb2b37515f140175808d0 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 14:50:13 -0500 Subject: [PATCH 3/8] Clean up g2o example --- Cargo.toml | 7 ---- examples/g2o-rerun.rs | 74 ------------------------------------- examples/g2o.rs | 86 +++++++++++++++++++++++++++++++++++-------- 3 files changed, 71 insertions(+), 96 deletions(-) delete mode 100644 examples/g2o-rerun.rs diff --git a/Cargo.toml b/Cargo.toml index 8e87638..a8a6d83 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -80,13 +80,6 @@ matrixcompare = "0.3.0" pretty_env_logger = "0.5" nalgebra = { version = "0.33.2", features = ["compare"] } -[[example]] -name = "g2o" - -[[example]] -name = "g2o-rerun" -required-features = ["rerun"] - [[example]] name = "serde" required-features = ["serde", "serde_json"] diff --git a/examples/g2o-rerun.rs b/examples/g2o-rerun.rs deleted file mode 100644 index 2b574fc..0000000 --- a/examples/g2o-rerun.rs +++ /dev/null @@ -1,74 +0,0 @@ -use std::{ - env, - net::{SocketAddr, SocketAddrV4}, - time::Instant, -}; - -use factrs::{ - optimizers::{GaussNewton, GraphOptimizer, Optimizer}, - rerun::RerunObserver, - utils::load_g20, - variables::*, -}; -use rerun::{Arrows2D, Arrows3D, Points2D, Points3D}; - -fn main() -> Result<(), Box> { - // ---------------------- Parse Arguments & Load data ---------------------- // - let args: Vec = env::args().collect(); - if args.len() < 2 { - println!("Usage: {} ", args[0]); - return Ok(()); - } - - let filename = &args[1]; - let obj = if args.len() >= 3 { &args[2] } else { "arrows" }; - - pretty_env_logger::init(); - - // Load the graph from the g2o file - let (graph, init) = load_g20(filename); - println!("File loaded"); - let dim = if init.filter::().count() != 0 { - "se2" - } else if init.filter::().count() != 0 { - "se3" - } else { - panic!("Graph doesn't have SE2 or SE3 variables"); - }; - - // ------------------------- Connect to rerun ------------------------- // - // Setup the rerun & the callback - let socket = SocketAddrV4::new("172.31.65.81".parse()?, 9876); - let rec = rerun::RecordingStreamBuilder::new("rerun_example_dna_abacus") - .connect_opts(SocketAddr::V4(socket), rerun::default_flush_timeout())?; - - let mut optimizer: GaussNewton = GaussNewton::new(graph); - let topic = "base/solution"; - match (dim, obj) { - ("se2", "points") => { - let callback = RerunObserver::::new(rec, topic); - optimizer.observers.add(callback) - } - ("se2", "arrows") => { - let callback = RerunObserver::::new(rec, topic); - optimizer.observers.add(callback) - } - ("se3", "points") => { - let callback = RerunObserver::::new(rec, topic); - optimizer.observers.add(callback) - } - ("se3", "arrows") => { - let callback = RerunObserver::::new(rec, topic); - optimizer.observers.add(callback) - } - _ => panic!("Invalid arguments"), - }; - - // ------------------------- Optimize ------------------------- // - let start = Instant::now(); - let _result = optimizer.optimize(init); - let duration = start.elapsed(); - - println!("Optimization took: {:?}", duration); - Ok(()) -} diff --git a/examples/g2o.rs b/examples/g2o.rs index 6ba81b2..cdcf319 100644 --- a/examples/g2o.rs +++ b/examples/g2o.rs @@ -3,36 +3,92 @@ use std::{env, time::Instant}; use factrs::{ optimizers::{GaussNewton, GraphOptimizer, Optimizer}, utils::load_g20, + variables::*, }; -fn main() { + +#[cfg(feature = "rerun")] +use factrs::rerun::RerunObserver; +#[cfg(feature = "rerun")] +use rerun::{Arrows2D, Arrows3D, Points2D, Points3D}; +#[cfg(feature = "rerun")] +use std::net::{SocketAddr, SocketAddrV4}; + +// Setups rerun and a callback for iteratively sending to rerun +// Must run with --features rerun for it to work +#[cfg(feature = "rerun")] +fn rerun_init(opt: &mut GaussNewton, dim: &str, obj: &str) { + // Setup the rerun & the callback + let socket = SocketAddrV4::new("172.31.65.81".parse().unwrap(), 9876); + let rec = rerun::RecordingStreamBuilder::new("rerun_example_dna_abacus") + .connect_tcp_opts(SocketAddr::V4(socket), rerun::default_flush_timeout()) + .unwrap(); + + let topic = "base/solution"; + + match (dim, obj) { + ("se2", "points") => { + let callback = RerunObserver::::new(rec, topic); + opt.observers.add(callback) + } + ("se2", "arrows") => { + let callback = RerunObserver::::new(rec, topic); + opt.observers.add(callback) + } + ("se3", "points") => { + let callback = RerunObserver::::new(rec, topic); + opt.observers.add(callback) + } + ("se3", "arrows") => { + let callback = RerunObserver::::new(rec, topic); + opt.observers.add(callback) + } + _ => panic!("Invalid arguments"), + }; +} + +#[cfg(not(feature = "rerun"))] +fn rerun_init(_opt: &mut GaussNewton, _dim: &str, _obj: &str) {} + +fn main() -> Result<(), Box> { + // ---------------------- Parse Arguments & Load data ---------------------- // let args: Vec = env::args().collect(); if args.len() < 2 { - println!("Usage: {} ", args[0]); - return; + println!("Usage: {} ", args[0]); + return Ok(()); } - let filename = &args[1]; pretty_env_logger::init(); // Load the graph from the g2o file + let filename = &args[1]; let (graph, init) = load_g20(filename); - let to_solve = init.clone(); println!("File loaded"); - // Optimize with GaussNewton + // Make optimizer let mut optimizer: GaussNewton = GaussNewton::new(graph); + + // Connect to rerun if it's been enabled + if cfg!(feature = "rerun") { + let obj = if args.len() >= 3 { &args[2] } else { "arrows" }; + let dim = if init.filter::().count() != 0 { + "se2" + } else if init.filter::().count() != 0 { + "se3" + } else { + panic!("Graph doesn't have SE2 or SE3 variables"); + }; + rerun_init(&mut optimizer, dim, obj); + } + + // ------------------------- Optimize ------------------------- // let start = Instant::now(); - let result = optimizer.optimize(to_solve); + let result = optimizer.optimize(init); let duration = start.elapsed(); - println!("Optimization took: {:?}", duration); - match result { - Ok(_sol) => { - println!("Optimization successful!"); - } - Err(e) => { - println!("Optimization failed: {:?}", e); - } + Ok(_) => println!("Optimization converged!"), + Err(e) => println!("Optimization failed: {:?}", e), } + println!("Optimization took: {:?}", duration); + Ok(()) } From f7057388c84eee8e52a9eb33b6cf63c317ddb4d3 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 21:37:00 -0500 Subject: [PATCH 4/8] Switch from ahash -> foldhash --- Cargo.lock | 10 +++++++--- Cargo.toml | 5 +---- src/containers/order.rs | 2 +- src/containers/values.rs | 14 +++----------- src/linear/graph.rs | 2 +- 5 files changed, 13 insertions(+), 20 deletions(-) diff --git a/Cargo.lock b/Cargo.lock index 8f594e7..6723b34 100644 --- a/Cargo.lock +++ b/Cargo.lock @@ -27,7 +27,6 @@ dependencies = [ "const-random", "getrandom", "once_cell", - "serde", "version_check", "zerocopy", ] @@ -831,11 +830,11 @@ checksum = "b90ca2580b73ab6a1f724b76ca11ab632df820fd6040c336200d2c1df7b3c82c" name = "factrs" version = "0.1.0" dependencies = [ - "ahash", "downcast-rs", "factrs-proc", "faer", "faer-ext", + "foldhash", "log", "matrixcompare", "nalgebra", @@ -880,7 +879,6 @@ dependencies = [ "paste", "rayon", "reborrow", - "serde", ] [[package]] @@ -944,6 +942,12 @@ version = "1.0.7" source = "registry+https://github.com/rust-lang/crates.io-index" checksum = "3f9eec918d3f24069decb9af1554cad7c880e2da24a9afd88aca000531ab82c1" +[[package]] +name = "foldhash" +version = "0.1.3" +source = "registry+https://github.com/rust-lang/crates.io-index" +checksum = "f81ec6369c545a7d40e4589b5597581fa1c441fe1cce96dd1de43159910a36a2" + [[package]] name = "foreign_vec" version = "0.1.0" diff --git a/Cargo.toml b/Cargo.toml index a8a6d83..f1e0894 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -19,8 +19,7 @@ exclude = ["factrs-typetag"] rustdoc-args = ["--html-in-header", "assets/katex-header.html"] [dependencies] -# base -ahash = "0.8.11" +foldhash = "0.1.3" paste = "1.0.15" downcast-rs = "1.2.1" log = "0.4.22" @@ -66,8 +65,6 @@ serde = [ "dep:typetag", "factrs-proc/serde", "nalgebra/serde-serialize", - "faer/serde", - "ahash/serde", ] # just used for examples serde_json = ["dep:serde_json"] diff --git a/src/containers/order.rs b/src/containers/order.rs index 0373bd6..b42a9c5 100644 --- a/src/containers/order.rs +++ b/src/containers/order.rs @@ -1,6 +1,6 @@ use std::collections::hash_map::Iter as HashMapIter; -use ahash::HashMap; +use foldhash::HashMap; use super::{Key, Symbol, Values}; diff --git a/src/containers/values.rs b/src/containers/values.rs index 84eeeca..8e1ee84 100644 --- a/src/containers/values.rs +++ b/src/containers/values.rs @@ -1,6 +1,6 @@ use std::{collections::hash_map::Entry, default::Default, fmt, iter::IntoIterator}; -use ahash::AHashMap; +use foldhash::HashMap; use super::{DefaultSymbol, Key, Symbol, TypedSymbol}; use crate::{ @@ -29,10 +29,10 @@ use crate::{ /// values.insert(X(0), x); /// ``` -#[derive(Clone)] +#[derive(Clone, Default)] #[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))] pub struct Values { - values: AHashMap>, + values: HashMap>, } impl Values { @@ -224,11 +224,3 @@ impl IntoIterator for Values { self.values.into_iter() } } - -impl Default for Values { - fn default() -> Self { - Self { - values: AHashMap::new(), - } - } -} diff --git a/src/linear/graph.rs b/src/linear/graph.rs index a4060ad..6a4988a 100644 --- a/src/linear/graph.rs +++ b/src/linear/graph.rs @@ -115,8 +115,8 @@ impl LinearGraph { #[cfg(test)] mod test { - use ahash::HashMap; use faer_ext::IntoNalgebra; + use foldhash::HashMap; use matrixcompare::assert_matrix_eq; use super::*; From 07785127285cdae057c50ab178f688ab5e46239f Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 21:58:48 -0500 Subject: [PATCH 5/8] Clean up serde example --- examples/gps.rs | 2 ++ examples/serde.rs | 26 ++++++++++++-------------- factrs-proc/src/variable.rs | 2 +- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/examples/gps.rs b/examples/gps.rs index 97222da..1ee97fa 100644 --- a/examples/gps.rs +++ b/examples/gps.rs @@ -26,6 +26,8 @@ use factrs::{ use factrs::variables::{VectorVar2, SE2}; #[derive(Clone, Debug)] +// Enable serialization if it's desired +#[cfg_attr(feature = "serde", derive(serde::Serialize, serde::Deserialize))] pub struct GpsResidual { meas: VectorVar2, } diff --git a/examples/serde.rs b/examples/serde.rs index 0e307b0..26aca90 100644 --- a/examples/serde.rs +++ b/examples/serde.rs @@ -2,48 +2,46 @@ use factrs::{ assign_symbols, containers::{Graph, Values}, fac, - noise::GaussianNoise, residuals::{BetweenResidual, PriorResidual}, robust::GemanMcClure, variables::{SE2, SO2}, }; -assign_symbols!(X: SO2, SE2); +assign_symbols!(X: SO2; Y: SE2); fn main() { - // ------------------------- Try with values ------------------------- // + // ------------------------- Serialize values ------------------------- // let x = SO2::from_theta(0.6); let y = SE2::new(1.0, 2.0, 0.3); let mut values = Values::new(); values.insert(X(0), x.clone()); - values.insert(X(1), y.clone()); + values.insert(Y(1), y.clone()); + + println!("------ Serializing Values ------"); let serialized = serde_json::to_string_pretty(&values).unwrap(); println!("serialized = {}", serialized); // Convert the JSON string back to a Point. let deserialized: Values = serde_json::from_str(&serialized).unwrap(); - println!("deserialized = {}", deserialized); + println!("deserialized = {:#?}", deserialized); - // ------------------------- Try with graph ------------------------- // + // ------------------------- Serialize graph ------------------------- // let prior = PriorResidual::new(x); let bet = BetweenResidual::new(y); - let prior = fac![ - prior, - X(0), - GaussianNoise::from_scalar_cov(0.1), - GemanMcClure::default() - ]; - let bet = fac![bet, (X(0), X(1)), GaussianNoise::from_scalar_cov(10.0)]; + let prior = fac![prior, X(0), 0.1 as cov, GemanMcClure::default()]; + let bet = fac![bet, (Y(0), Y(1)), 10.0 as cov]; let mut graph = Graph::new(); graph.add_factor(prior); graph.add_factor(bet); + println!("\n\n------ Serializing Graph ------"); + let serialized = serde_json::to_string_pretty(&graph).unwrap(); println!("serialized = {}", serialized); let deserialized: Graph = serde_json::from_str(&serialized).unwrap(); - println!("deserialized = {:?}", deserialized); + println!("deserialized = {:#?}", deserialized); } diff --git a/factrs-proc/src/variable.rs b/factrs-proc/src/variable.rs index 798e860..40d3018 100644 --- a/factrs-proc/src/variable.rs +++ b/factrs-proc/src/variable.rs @@ -118,7 +118,7 @@ fn tag_all(kind: &TokenStream2, name: &str) -> TokenStream2 { #name_between, (|deserializer| typetag::__private::Result::Ok( typetag::__private::Box::new( - typetag::__private::erased_serde::deserialize::>(deserializer)? + typetag::__private::erased_serde::deserialize::>(deserializer)? ), )) as typetag::__private::DeserializeFn<::Object>, ) From 85eb2467638562759595709e897f0dde3207eb19 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 22:04:01 -0500 Subject: [PATCH 6/8] Remove serde_json feature --- .github/workflows/ci.yml | 2 +- Cargo.toml | 6 ++---- tests/custom_noise.rs | 1 - tests/custom_residual.rs | 1 - tests/custom_robust.rs | 1 - tests/custom_variable.rs | 1 - tests/serde.rs | 1 - 7 files changed, 3 insertions(+), 10 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 0af35f0..bf5f4af 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -49,7 +49,7 @@ jobs: - name: default run: cargo test - name: serde - run: cargo test --features="serde,serde_json" + run: cargo test --features serde - name: f32 run: cargo test --features f32 - name: left diff --git a/Cargo.toml b/Cargo.toml index f1e0894..28921a5 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -39,7 +39,6 @@ matrixcompare = { version = "0.3" } # serialization serde = { version = "1.0.214", optional = true } typetag = { version = "0.2.18", optional = true, path = "./factrs-typetag" } -serde_json = { version = "1.0.132", optional = true } # rerun support rerun = { version = "0.20", optional = true, default-features = false, features = [ @@ -66,8 +65,6 @@ serde = [ "factrs-proc/serde", "nalgebra/serde-serialize", ] -# just used for examples -serde_json = ["dep:serde_json"] # Support for conversion to rerun variable types rerun = ["dep:rerun"] @@ -76,7 +73,8 @@ rerun = ["dep:rerun"] matrixcompare = "0.3.0" pretty_env_logger = "0.5" nalgebra = { version = "0.33.2", features = ["compare"] } +serde_json = { version = "1.0.132" } [[example]] name = "serde" -required-features = ["serde", "serde_json"] +required-features = ["serde"] diff --git a/tests/custom_noise.rs b/tests/custom_noise.rs index 62fe083..7c4a3e9 100644 --- a/tests/custom_noise.rs +++ b/tests/custom_noise.rs @@ -30,7 +30,6 @@ impl fmt::Display for DoubleCovariance { } #[cfg(feature = "serde")] -#[cfg(feature = "serde_json")] mod ser_de { use factrs::linalg::vectorx; diff --git a/tests/custom_residual.rs b/tests/custom_residual.rs index e8d044f..49defc1 100644 --- a/tests/custom_residual.rs +++ b/tests/custom_residual.rs @@ -43,7 +43,6 @@ impl fmt::Display for XPrior { // TODO: Some tests to make sure it optimizes #[cfg(feature = "serde")] -#[cfg(feature = "serde_json")] mod ser_de { use factrs::{containers::Values, symbols::X, traits::Residual}; diff --git a/tests/custom_robust.rs b/tests/custom_robust.rs index 294872e..8a41b50 100644 --- a/tests/custom_robust.rs +++ b/tests/custom_robust.rs @@ -18,7 +18,6 @@ impl RobustCost for DoubleL2 { factrs::test_robust!(DoubleL2); #[cfg(feature = "serde")] -#[cfg(feature = "serde_json")] mod ser_de { use super::*; diff --git a/tests/custom_variable.rs b/tests/custom_variable.rs index 4aea6ba..7ed51ae 100644 --- a/tests/custom_variable.rs +++ b/tests/custom_variable.rs @@ -72,7 +72,6 @@ impl fmt::Debug for MyVar { factrs::test_variable!(MyVar); #[cfg(feature = "serde")] -#[cfg(feature = "serde_json")] mod ser_de { use super::*; use factrs::{ diff --git a/tests/serde.rs b/tests/serde.rs index 29430ab..a62a331 100644 --- a/tests/serde.rs +++ b/tests/serde.rs @@ -1,5 +1,4 @@ #[cfg(feature = "serde")] -#[cfg(feature = "serde_json")] mod ser_de { use factrs::{ containers::Values, residuals::PriorResidual, symbols::X, traits::Residual, From 0951c2317fd990ea8fc283f46a11105572edf143 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Mon, 9 Dec 2024 22:07:44 -0500 Subject: [PATCH 7/8] Fix clippy lint --- src/residuals/prior.rs | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/src/residuals/prior.rs b/src/residuals/prior.rs index 23d6f7f..8ce0a01 100644 --- a/src/residuals/prior.rs +++ b/src/residuals/prior.rs @@ -50,7 +50,10 @@ mod test { use super::*; use crate::{ - containers::Values, linalg::{vectorx, DefaultAllocator, Diff, DualAllocator, NumericalDiff}, symbols::X, variables::{VectorVar3, SE3, SO3} + containers::Values, + linalg::{vectorx, DefaultAllocator, Diff, DualAllocator, NumericalDiff}, + symbols::X, + variables::{VectorVar3, SE3, SO3}, }; #[cfg(not(feature = "f32"))] From 1e4dc78907f5da19e16f5381ad8944b2481bdce6 Mon Sep 17 00:00:00 2001 From: Easton Potokar Date: Tue, 10 Dec 2024 10:08:51 -0500 Subject: [PATCH 8/8] Add g2o data, document examples in readme --- Cargo.toml | 1 + README.md | 24 +- examples/data/M3500.g2o | 8953 ++++++++++++++++++++++++++++++ examples/data/parking-garage.g2o | 7936 ++++++++++++++++++++++++++ examples/data/sphere2500.g2o | 7449 +++++++++++++++++++++++++ examples/g2o.rs | 2 +- 6 files changed, 24362 insertions(+), 3 deletions(-) create mode 100644 examples/data/M3500.g2o create mode 100644 examples/data/parking-garage.g2o create mode 100644 examples/data/sphere2500.g2o diff --git a/Cargo.toml b/Cargo.toml index 28921a5..5dfab38 100644 --- a/Cargo.toml +++ b/Cargo.toml @@ -10,6 +10,7 @@ repository = "https://github.com/rpl-cmu/factrs" keywords = ["nonlinear", "optimization", "robotics", "estimation", "SLAM"] categories = ["science::robotics", "mathematics"] rust-version = "1.81" +exclude = ["examples/data/*"] [workspace] members = ["factrs-proc"] diff --git a/README.md b/README.md index 43aee6c..e7d6fbd 100644 --- a/README.md +++ b/README.md @@ -20,7 +20,25 @@ Currently, it supports the following features We recommend you checkout the [docs](https://docs.rs/factrs/latest/factrs/) for more info. -# Example +# Examples +There's a number of examples found in the [examples](/examples/) folder, including loading g20 files, serialization, and custom factors. + +To run any of the examples, simply clone this repository and run, +```bash +cargo run --release --example g20 ./examples/data/M3500.g20 +``` +to visualize the optimization steps with [rerun](https://rerun.io) simply add `--features rerun` to the above command. + +Running the other examples can be done similarly, +```bash +cargo run --release --example serde --features serde +cargo run --release --example gps +``` + +Additionally, we recommend checking out the [tests](/tests/) folder for more examples of custom noise models, residuals, robust kernels, and variables. + +

+Full Example ```rust use factrs::{ @@ -55,7 +73,7 @@ graph.add_factor(factor); let res = BetweenResidual::new(y.minus(&x)); let robust = Huber::default(); let factor = fac![res, (X(0), X(1)), 0.1 as std, robust]; -// The same as above, but verbose +// fac! is syntactic sugar for the following // let noise = GaussianNoise::from_scalar_sigma(0.1); // let factor = FactorBuilder::new2(res, X(0), X(1)) // .noise(noise) @@ -73,6 +91,8 @@ Simply add via cargo as you do any rust dependency, ```bash cargo add factrs ``` +
+ # Contributions diff --git a/examples/data/M3500.g2o b/examples/data/M3500.g2o new file mode 100644 index 0000000..e3a7a67 --- /dev/null +++ b/examples/data/M3500.g2o @@ -0,0 +1,8953 @@ +VERTEX_SE2 0 0.000000 0.000000 0.000000 +VERTEX_SE2 1 1.030390 0.011350 -0.012958 +VERTEX_SE2 2 2.043445 -0.060422 -0.026183 +VERTEX_SE2 3 3.070548 -0.094779 -0.021350 +VERTEX_SE2 4 3.079976 0.909609 1.545440 +VERTEX_SE2 5 3.091176 1.925681 1.529136 +VERTEX_SE2 6 3.127018 2.948966 1.540117 +VERTEX_SE2 7 3.153237 3.906347 1.551018 +VERTEX_SE2 8 3.146655 2.882457 -1.542222 +VERTEX_SE2 9 3.189873 1.859834 -1.550024 +VERTEX_SE2 10 3.232959 0.857162 -1.526533 +VERTEX_SE2 11 3.295225 -0.118283 -1.555156 +VERTEX_SE2 12 3.254125 0.878076 1.601114 +VERTEX_SE2 13 3.205708 1.867709 1.584594 +VERTEX_SE2 14 3.183765 2.813370 1.581993 +VERTEX_SE2 15 3.166141 3.813245 1.610227 +VERTEX_SE2 16 4.189940 3.891536 0.074927 +VERTEX_SE2 17 5.169481 3.985015 0.099012 +VERTEX_SE2 18 6.119067 4.109076 0.087511 +VERTEX_SE2 19 7.105732 4.214917 0.080214 +VERTEX_SE2 20 7.141394 3.198185 -1.458906 +VERTEX_SE2 21 7.247678 2.205394 -1.493004 +VERTEX_SE2 22 7.333523 1.220359 -1.505918 +VERTEX_SE2 23 7.404637 0.233471 -1.530201 +VERTEX_SE2 24 7.357714 1.234401 1.609539 +VERTEX_SE2 25 7.313477 2.248799 1.609569 +VERTEX_SE2 26 7.275161 3.281080 1.631976 +VERTEX_SE2 27 7.223238 4.268890 1.611072 +VERTEX_SE2 28 6.244268 4.181001 -3.108034 +VERTEX_SE2 29 5.213314 4.167673 3.114462 +VERTEX_SE2 30 4.201321 4.178683 3.079260 +VERTEX_SE2 31 3.211421 4.232638 3.109852 +VERTEX_SE2 32 3.233726 5.206446 1.540242 +VERTEX_SE2 33 3.254911 6.248845 1.562256 +VERTEX_SE2 34 3.246679 7.239778 1.519471 +VERTEX_SE2 35 3.268289 8.235969 1.505060 +VERTEX_SE2 36 2.273681 8.290647 3.099220 +VERTEX_SE2 37 1.269124 8.322142 3.096055 +VERTEX_SE2 38 0.231102 8.354751 3.063734 +VERTEX_SE2 39 -0.772624 8.426293 3.035670 +VERTEX_SE2 40 -0.932611 7.452764 -1.668100 +VERTEX_SE2 41 -1.060044 6.475867 -1.657017 +VERTEX_SE2 42 -1.115865 5.474293 -1.626969 +VERTEX_SE2 43 -1.184324 4.490168 -1.651087 +VERTEX_SE2 44 -1.250783 3.513632 -1.662830 +VERTEX_SE2 45 -1.382888 2.525478 -1.678048 +VERTEX_SE2 46 -1.492358 1.528920 -1.688550 +VERTEX_SE2 47 -1.643215 0.540155 -1.669743 +VERTEX_SE2 48 -1.537692 1.484096 1.444017 +VERTEX_SE2 49 -1.421334 2.494886 1.435083 +VERTEX_SE2 50 -1.311092 3.504736 1.415892 +VERTEX_SE2 51 -1.163303 4.546680 1.414529 +VERTEX_SE2 52 -0.192621 4.382800 -0.146461 +VERTEX_SE2 53 0.828362 4.241243 -0.154862 +VERTEX_SE2 54 1.801524 4.099234 -0.185546 +VERTEX_SE2 55 2.793364 3.897462 -0.179698 +VERTEX_SE2 56 2.613717 2.928990 -1.752548 +VERTEX_SE2 57 2.411305 1.917923 -1.769509 +VERTEX_SE2 58 2.206055 0.956121 -1.784349 +VERTEX_SE2 59 2.003264 -0.033624 -1.780020 +VERTEX_SE2 60 1.012493 0.156191 2.956750 +VERTEX_SE2 61 0.037604 0.342607 2.965819 +VERTEX_SE2 62 -0.925976 0.526622 2.990580 +VERTEX_SE2 63 -1.916578 0.714885 2.983129 +VERTEX_SE2 64 -1.744636 1.698687 1.435739 +VERTEX_SE2 65 -1.588202 2.724909 1.422657 +VERTEX_SE2 66 -1.453347 3.706961 1.397705 +VERTEX_SE2 67 -1.274565 4.639548 1.388580 +VERTEX_SE2 68 -1.442734 3.675704 -1.749330 +VERTEX_SE2 69 -1.655709 2.694255 -1.715262 +VERTEX_SE2 70 -1.801436 1.674805 -1.700261 +VERTEX_SE2 71 -1.923546 0.645435 -1.701897 +VERTEX_SE2 72 -2.909516 0.771426 2.996463 +VERTEX_SE2 73 -3.864270 0.941897 2.963812 +VERTEX_SE2 74 -4.836396 1.105244 2.962148 +VERTEX_SE2 75 -5.800781 1.286242 2.984817 +VERTEX_SE2 76 -5.945921 0.315152 -1.733813 +VERTEX_SE2 77 -6.077718 -0.690784 -1.798734 +VERTEX_SE2 78 -6.300417 -1.694369 -1.764727 +VERTEX_SE2 79 -6.501243 -2.676732 -1.755221 +VERTEX_SE2 80 -7.461447 -2.487225 2.989009 +VERTEX_SE2 81 -8.465250 -2.352287 2.987013 +VERTEX_SE2 82 -9.442723 -2.167681 2.967257 +VERTEX_SE2 83 -10.437700 -1.998443 2.945776 +VERTEX_SE2 84 -10.620572 -3.015367 -1.782414 +VERTEX_SE2 85 -10.808214 -3.982218 -1.773639 +VERTEX_SE2 86 -10.997685 -4.957062 -1.762909 +VERTEX_SE2 87 -11.166296 -5.935779 -1.751842 +VERTEX_SE2 88 -10.143208 -6.124294 -0.214732 +VERTEX_SE2 89 -9.161898 -6.353766 -0.199936 +VERTEX_SE2 90 -8.170874 -6.560091 -0.169925 +VERTEX_SE2 91 -7.150702 -6.732116 -0.178941 +VERTEX_SE2 92 -6.993320 -5.772380 1.373649 +VERTEX_SE2 93 -6.860082 -4.788670 1.358958 +VERTEX_SE2 94 -6.669764 -3.835966 1.359176 +VERTEX_SE2 95 -6.427687 -2.841918 1.359541 +VERTEX_SE2 96 -7.457751 -2.640779 2.932071 +VERTEX_SE2 97 -8.471609 -2.411808 2.943440 +VERTEX_SE2 98 -9.452931 -2.254922 2.932869 +VERTEX_SE2 99 -10.464400 -2.016258 2.915544 +VERTEX_SE2 100 -9.501432 -2.227667 -0.236436 +VERTEX_SE2 101 -8.497857 -2.436835 -0.212395 +VERTEX_SE2 102 -7.521962 -2.626562 -0.214803 +VERTEX_SE2 103 -6.538331 -2.816443 -0.213563 +VERTEX_SE2 104 -7.524835 -2.606118 2.950067 +VERTEX_SE2 105 -8.511257 -2.419761 2.968841 +VERTEX_SE2 106 -9.460872 -2.256235 2.950946 +VERTEX_SE2 107 -10.454240 -2.090899 2.957034 +VERTEX_SE2 108 -10.239738 -1.073953 1.399324 +VERTEX_SE2 109 -10.091967 -0.076144 1.404125 +VERTEX_SE2 110 -9.914068 0.902969 1.419992 +VERTEX_SE2 111 -9.762182 1.873547 1.428189 +VERTEX_SE2 112 -9.940470 0.895680 -1.736311 +VERTEX_SE2 113 -10.112213 -0.111731 -1.746880 +VERTEX_SE2 114 -10.298300 -1.117058 -1.758256 +VERTEX_SE2 115 -10.501070 -2.108193 -1.772713 +VERTEX_SE2 116 -9.538664 -2.296112 -0.248753 +VERTEX_SE2 117 -8.568047 -2.573933 -0.267950 +VERTEX_SE2 118 -7.620847 -2.839503 -0.301875 +VERTEX_SE2 119 -6.678604 -3.127140 -0.262532 +VERTEX_SE2 120 -7.667943 -2.916333 2.881278 +VERTEX_SE2 121 -8.637104 -2.629092 2.917303 +VERTEX_SE2 122 -9.598755 -2.394117 2.925141 +VERTEX_SE2 123 -10.603866 -2.209252 2.933300 +VERTEX_SE2 124 -10.792151 -3.141398 -1.797300 +VERTEX_SE2 125 -11.001430 -4.124275 -1.818424 +VERTEX_SE2 126 -11.271552 -5.114358 -1.818418 +VERTEX_SE2 127 -11.475580 -6.056302 -1.825616 +VERTEX_SE2 128 -10.482089 -6.272707 -0.240656 +VERTEX_SE2 129 -9.508969 -6.525724 -0.255332 +VERTEX_SE2 130 -8.541861 -6.805277 -0.261048 +VERTEX_SE2 131 -7.574693 -7.074211 -0.304722 +VERTEX_SE2 132 -7.840205 -8.052279 -1.883492 +VERTEX_SE2 133 -8.157854 -9.004781 -1.882927 +VERTEX_SE2 134 -8.463107 -9.939942 -1.876509 +VERTEX_SE2 135 -8.722697 -10.895179 -1.862480 +VERTEX_SE2 136 -8.394898 -9.916348 1.278850 +VERTEX_SE2 137 -8.091183 -8.968934 1.278504 +VERTEX_SE2 138 -7.803504 -7.988848 1.265976 +VERTEX_SE2 139 -7.483992 -7.002690 1.239498 +VERTEX_SE2 140 -7.831458 -7.941427 -1.896082 +VERTEX_SE2 141 -8.151414 -8.903782 -1.906127 +VERTEX_SE2 142 -8.473358 -9.889361 -1.871642 +VERTEX_SE2 143 -8.755190 -10.870870 -1.872585 +VERTEX_SE2 144 -8.423714 -9.925457 1.274135 +VERTEX_SE2 145 -8.157317 -8.986692 1.259871 +VERTEX_SE2 146 -7.829323 -8.051197 1.267985 +VERTEX_SE2 147 -7.515148 -7.088232 1.247742 +VERTEX_SE2 148 -6.533969 -7.404101 -0.292888 +VERTEX_SE2 149 -5.551699 -7.637584 -0.267102 +VERTEX_SE2 150 -4.584401 -7.900949 -0.282661 +VERTEX_SE2 151 -3.636057 -8.134416 -0.261897 +VERTEX_SE2 152 -3.363126 -7.139837 1.326103 +VERTEX_SE2 153 -3.129259 -6.183602 1.280756 +VERTEX_SE2 154 -2.823349 -5.247990 1.287007 +VERTEX_SE2 155 -2.562161 -4.326025 1.299302 +VERTEX_SE2 156 -2.844616 -5.264033 -1.800378 +VERTEX_SE2 157 -3.116983 -6.242031 -1.799785 +VERTEX_SE2 158 -3.363858 -7.215442 -1.814163 +VERTEX_SE2 159 -3.646316 -8.177528 -1.777860 +VERTEX_SE2 160 -3.442185 -7.182909 1.403610 +VERTEX_SE2 161 -3.279802 -6.219495 1.390581 +VERTEX_SE2 162 -3.091618 -5.208705 1.399302 +VERTEX_SE2 163 -2.941536 -4.255811 1.418005 +VERTEX_SE2 164 -3.095871 -5.199891 -1.721475 +VERTEX_SE2 165 -3.225365 -6.194593 -1.737465 +VERTEX_SE2 166 -3.417967 -7.128217 -1.756961 +VERTEX_SE2 167 -3.587966 -8.144379 -1.758007 +VERTEX_SE2 168 -4.581467 -7.975034 2.936363 +VERTEX_SE2 169 -5.556436 -7.771364 2.958261 +VERTEX_SE2 170 -6.507569 -7.588331 2.943883 +VERTEX_SE2 171 -7.487467 -7.381884 2.927650 +VERTEX_SE2 172 -7.280545 -6.398262 1.337100 +VERTEX_SE2 173 -7.054335 -5.437332 1.346987 +VERTEX_SE2 174 -6.850702 -4.486838 1.317921 +VERTEX_SE2 175 -6.634349 -3.504051 1.308307 +VERTEX_SE2 176 -6.899060 -4.497346 -1.831823 +VERTEX_SE2 177 -7.144233 -5.474339 -1.830214 +VERTEX_SE2 178 -7.374369 -6.423558 -1.830753 +VERTEX_SE2 179 -7.624575 -7.357562 -1.806978 +VERTEX_SE2 180 -7.879447 -8.332849 -1.826028 +VERTEX_SE2 181 -8.111676 -9.294292 -1.825694 +VERTEX_SE2 182 -8.359222 -10.269390 -1.818725 +VERTEX_SE2 183 -8.626693 -11.244634 -1.844319 +VERTEX_SE2 184 -9.560145 -10.986767 2.862251 +VERTEX_SE2 185 -10.552780 -10.710357 2.839546 +VERTEX_SE2 186 -11.499477 -10.445483 2.853434 +VERTEX_SE2 187 -12.463908 -10.173503 2.891149 +VERTEX_SE2 188 -12.228789 -9.213301 1.318819 +VERTEX_SE2 189 -11.995935 -8.252037 1.294050 +VERTEX_SE2 190 -11.726134 -7.260630 1.292486 +VERTEX_SE2 191 -11.468619 -6.308426 1.281927 +VERTEX_SE2 192 -12.399029 -5.982763 2.895517 +VERTEX_SE2 193 -13.366254 -5.794292 2.902696 +VERTEX_SE2 194 -14.335478 -5.575552 2.880452 +VERTEX_SE2 195 -15.309022 -5.327732 2.897210 +VERTEX_SE2 196 -15.552984 -6.287275 -1.806620 +VERTEX_SE2 197 -15.801358 -7.271382 -1.808807 +VERTEX_SE2 198 -16.032326 -8.237915 -1.804324 +VERTEX_SE2 199 -16.299597 -9.222450 -1.812602 +VERTEX_SE2 200 -17.280428 -8.957540 2.922868 +VERTEX_SE2 201 -18.229257 -8.785944 2.932369 +VERTEX_SE2 202 -19.195801 -8.579588 2.935027 +VERTEX_SE2 203 -20.163926 -8.370476 2.941354 +VERTEX_SE2 204 -20.394941 -9.368273 -1.777256 +VERTEX_SE2 205 -20.584973 -10.313287 -1.777011 +VERTEX_SE2 206 -20.808153 -11.291883 -1.741464 +VERTEX_SE2 207 -20.998789 -12.283939 -1.750337 +VERTEX_SE2 208 -20.785028 -11.302841 1.367883 +VERTEX_SE2 209 -20.581793 -10.305149 1.367217 +VERTEX_SE2 210 -20.373642 -9.348821 1.334481 +VERTEX_SE2 211 -20.142260 -8.360855 1.327812 +VERTEX_SE2 212 -19.179737 -8.594839 -0.245988 +VERTEX_SE2 213 -18.243865 -8.834471 -0.264465 +VERTEX_SE2 214 -17.254699 -9.083997 -0.214100 +VERTEX_SE2 215 -16.287843 -9.335128 -0.227133 +VERTEX_SE2 216 -16.031054 -8.388184 1.315317 +VERTEX_SE2 217 -15.750511 -7.414289 1.280939 +VERTEX_SE2 218 -15.504566 -6.460051 1.257163 +VERTEX_SE2 219 -15.194146 -5.518956 1.270341 +VERTEX_SE2 220 -15.493252 -6.478280 -1.841759 +VERTEX_SE2 221 -15.795847 -7.443869 -1.810693 +VERTEX_SE2 222 -16.023517 -8.431898 -1.810823 +VERTEX_SE2 223 -16.271316 -9.422797 -1.791713 +VERTEX_SE2 224 -16.033889 -8.466449 1.350267 +VERTEX_SE2 225 -15.783823 -7.484345 1.342822 +VERTEX_SE2 226 -15.574078 -6.472631 1.330758 +VERTEX_SE2 227 -15.317295 -5.546752 1.342068 +VERTEX_SE2 228 -14.323834 -5.780562 -0.252342 +VERTEX_SE2 229 -13.413275 -6.001900 -0.243007 +VERTEX_SE2 230 -12.461562 -6.262550 -0.231669 +VERTEX_SE2 231 -11.507012 -6.496820 -0.253158 +VERTEX_SE2 232 -11.732022 -7.458957 -1.862318 +VERTEX_SE2 233 -11.987321 -8.426996 -1.839421 +VERTEX_SE2 234 -12.264136 -9.363248 -1.863147 +VERTEX_SE2 235 -12.557162 -10.339908 -1.853382 +VERTEX_SE2 236 -11.585952 -10.612359 -0.288082 +VERTEX_SE2 237 -10.603818 -10.914629 -0.304501 +VERTEX_SE2 238 -9.615072 -11.183857 -0.371383 +VERTEX_SE2 239 -8.698336 -11.558783 -0.392138 +VERTEX_SE2 240 -9.605737 -11.162955 2.706892 +VERTEX_SE2 241 -10.479267 -10.756690 2.702220 +VERTEX_SE2 242 -11.370695 -10.315788 2.718632 +VERTEX_SE2 243 -12.310410 -9.874299 2.691813 +VERTEX_SE2 244 -12.721587 -10.743440 -2.006907 +VERTEX_SE2 245 -13.154478 -11.601001 -1.983304 +VERTEX_SE2 246 -13.567094 -12.516329 -1.984079 +VERTEX_SE2 247 -13.980558 -13.414895 -1.999081 +VERTEX_SE2 248 -14.400703 -14.327523 -2.017602 +VERTEX_SE2 249 -14.795720 -15.238380 -1.998697 +VERTEX_SE2 250 -15.174687 -16.156614 -1.988518 +VERTEX_SE2 251 -15.570043 -17.075353 -1.999927 +VERTEX_SE2 252 -15.119283 -16.149100 1.151643 +VERTEX_SE2 253 -14.684174 -15.215857 1.148889 +VERTEX_SE2 254 -14.255630 -14.313589 1.146406 +VERTEX_SE2 255 -13.823077 -13.393125 1.170306 +VERTEX_SE2 256 -14.217960 -14.317041 -1.933474 +VERTEX_SE2 257 -14.576124 -15.229564 -1.963201 +VERTEX_SE2 258 -14.979496 -16.150487 -1.929686 +VERTEX_SE2 259 -15.326582 -17.044412 -1.933981 +VERTEX_SE2 260 -14.995611 -16.102336 1.199549 +VERTEX_SE2 261 -14.677158 -15.148998 1.207488 +VERTEX_SE2 262 -14.355515 -14.226242 1.242762 +VERTEX_SE2 263 -14.060095 -13.301180 1.225472 +VERTEX_SE2 264 -13.121247 -13.628215 -0.370188 +VERTEX_SE2 265 -12.153768 -13.987812 -0.366261 +VERTEX_SE2 266 -11.225089 -14.346321 -0.352178 +VERTEX_SE2 267 -10.292801 -14.655541 -0.339660 +VERTEX_SE2 268 -10.592855 -15.614235 -1.910250 +VERTEX_SE2 269 -10.933932 -16.525471 -1.911003 +VERTEX_SE2 270 -11.279623 -17.492155 -1.849903 +VERTEX_SE2 271 -11.558199 -18.434106 -1.867699 +VERTEX_SE2 272 -10.570075 -18.712475 -0.269649 +VERTEX_SE2 273 -9.549204 -18.982934 -0.236076 +VERTEX_SE2 274 -8.573896 -19.217892 -0.253062 +VERTEX_SE2 275 -7.636620 -19.487215 -0.226923 +VERTEX_SE2 276 -7.411962 -18.447309 1.348197 +VERTEX_SE2 277 -7.187137 -17.485537 1.341126 +VERTEX_SE2 278 -6.974895 -16.528576 1.337573 +VERTEX_SE2 279 -6.758317 -15.538311 1.334583 +VERTEX_SE2 280 -5.822124 -15.782422 -0.251557 +VERTEX_SE2 281 -4.871593 -16.053241 -0.247368 +VERTEX_SE2 282 -3.921090 -16.319890 -0.251948 +VERTEX_SE2 283 -2.948898 -16.538391 -0.296225 +VERTEX_SE2 284 -3.916878 -16.228364 2.866395 +VERTEX_SE2 285 -4.855340 -15.934897 2.867544 +VERTEX_SE2 286 -5.790113 -15.704526 2.896606 +VERTEX_SE2 287 -6.776725 -15.502221 2.914318 +VERTEX_SE2 288 -7.027128 -16.452656 -1.822712 +VERTEX_SE2 289 -7.274523 -17.416595 -1.792885 +VERTEX_SE2 290 -7.515273 -18.418473 -1.834522 +VERTEX_SE2 291 -7.784102 -19.346841 -1.796912 +VERTEX_SE2 292 -8.752679 -19.126083 2.901518 +VERTEX_SE2 293 -9.755438 -18.887369 2.940789 +VERTEX_SE2 294 -10.698194 -18.685966 2.956106 +VERTEX_SE2 295 -11.657781 -18.462310 2.961102 +VERTEX_SE2 296 -11.863749 -19.467586 -1.706658 +VERTEX_SE2 297 -12.000124 -20.473272 -1.693248 +VERTEX_SE2 298 -12.149406 -21.425667 -1.709191 +VERTEX_SE2 299 -12.291615 -22.417976 -1.715679 +VERTEX_SE2 300 -13.273299 -22.253694 3.038341 +VERTEX_SE2 301 -14.232561 -22.121054 3.045365 +VERTEX_SE2 302 -15.202249 -22.013628 3.048038 +VERTEX_SE2 303 -16.168712 -21.895651 3.050643 +VERTEX_SE2 304 -16.088697 -20.912677 1.441613 +VERTEX_SE2 305 -15.957798 -19.924985 1.470473 +VERTEX_SE2 306 -15.864698 -18.930364 1.467563 +VERTEX_SE2 307 -15.739099 -17.941730 1.462649 +VERTEX_SE2 308 -16.737926 -17.838998 3.023509 +VERTEX_SE2 309 -17.740989 -17.728118 3.069814 +VERTEX_SE2 310 -18.751523 -17.671402 3.110373 +VERTEX_SE2 311 -19.784915 -17.645070 3.102971 +VERTEX_SE2 312 -19.821702 -18.660597 -1.581609 +VERTEX_SE2 313 -19.806428 -19.648576 -1.559154 +VERTEX_SE2 314 -19.799115 -20.621084 -1.557532 +VERTEX_SE2 315 -19.814066 -21.654913 -1.519352 +VERTEX_SE2 316 -20.809456 -21.688319 -3.061747 +VERTEX_SE2 317 -21.842491 -21.763755 -3.029103 +VERTEX_SE2 318 -22.814859 -21.858935 -3.054648 +VERTEX_SE2 319 -23.853507 -21.991320 -3.060824 +VERTEX_SE2 320 -23.939068 -20.988645 1.650161 +VERTEX_SE2 321 -24.052728 -20.017691 1.649406 +VERTEX_SE2 322 -24.131951 -19.005777 1.639093 +VERTEX_SE2 323 -24.190175 -18.026937 1.616149 +VERTEX_SE2 324 -25.203420 -18.061934 -3.115986 +VERTEX_SE2 325 -26.200606 -18.100876 -3.095587 +VERTEX_SE2 326 -27.249494 -18.133100 -3.086373 +VERTEX_SE2 327 -28.224739 -18.173922 -3.091231 +VERTEX_SE2 328 -27.211104 -18.163993 0.064374 +VERTEX_SE2 329 -26.204524 -18.108574 0.061102 +VERTEX_SE2 330 -25.225105 -18.055594 0.065611 +VERTEX_SE2 331 -24.239776 -17.980609 0.059431 +VERTEX_SE2 332 -24.151274 -18.944062 -1.510029 +VERTEX_SE2 333 -24.068760 -19.953554 -1.529094 +VERTEX_SE2 334 -24.047799 -20.969063 -1.491894 +VERTEX_SE2 335 -23.926621 -21.979305 -1.474933 +VERTEX_SE2 336 -22.898318 -21.844863 0.112777 +VERTEX_SE2 337 -21.914345 -21.713514 0.106339 +VERTEX_SE2 338 -20.955035 -21.630407 0.081086 +VERTEX_SE2 339 -19.926358 -21.587903 0.083615 +VERTEX_SE2 340 -20.023646 -20.592574 1.667585 +VERTEX_SE2 341 -20.112997 -19.592317 1.673936 +VERTEX_SE2 342 -20.219447 -18.601128 1.665329 +VERTEX_SE2 343 -20.315029 -17.595199 1.643120 +VERTEX_SE2 344 -19.279137 -17.530206 0.107090 +VERTEX_SE2 345 -18.264515 -17.406150 0.090611 +VERTEX_SE2 346 -17.243305 -17.310885 0.075439 +VERTEX_SE2 347 -16.235791 -17.235771 0.080640 +VERTEX_SE2 348 -16.346204 -16.281316 1.634710 +VERTEX_SE2 349 -16.409866 -15.299735 1.598341 +VERTEX_SE2 350 -16.438167 -14.264922 1.567367 +VERTEX_SE2 351 -16.397631 -13.263415 1.557179 +VERTEX_SE2 352 -16.406116 -14.269223 -1.554261 +VERTEX_SE2 353 -16.387636 -15.277675 -1.540474 +VERTEX_SE2 354 -16.344134 -16.261762 -1.532161 +VERTEX_SE2 355 -16.281744 -17.279942 -1.548640 +VERTEX_SE2 356 -16.303542 -16.279019 1.623230 +VERTEX_SE2 357 -16.380282 -15.263615 1.622721 +VERTEX_SE2 358 -16.446385 -14.260755 1.603694 +VERTEX_SE2 359 -16.475694 -13.301818 1.606208 +VERTEX_SE2 360 -16.469547 -14.367368 -1.555742 +VERTEX_SE2 361 -16.441222 -15.364934 -1.572624 +VERTEX_SE2 362 -16.402142 -16.425977 -1.554516 +VERTEX_SE2 363 -16.378149 -17.420296 -1.548955 +VERTEX_SE2 364 -16.407580 -16.394294 1.590525 +VERTEX_SE2 365 -16.438715 -15.352726 1.628877 +VERTEX_SE2 366 -16.493439 -14.379524 1.597907 +VERTEX_SE2 367 -16.540806 -13.364916 1.574339 +VERTEX_SE2 368 -17.545991 -13.339989 3.113959 +VERTEX_SE2 369 -18.536791 -13.284400 3.105104 +VERTEX_SE2 370 -19.555981 -13.244151 3.078011 +VERTEX_SE2 371 -20.497596 -13.167408 3.088366 +VERTEX_SE2 372 -20.574004 -14.173598 -1.605284 +VERTEX_SE2 373 -20.595461 -15.211385 -1.602801 +VERTEX_SE2 374 -20.620038 -16.227599 -1.578267 +VERTEX_SE2 375 -20.608133 -17.215289 -1.588278 +VERTEX_SE2 376 -21.594205 -17.190596 -3.131394 +VERTEX_SE2 377 -22.547926 -17.202346 -3.132665 +VERTEX_SE2 378 -23.513768 -17.259579 3.136580 +VERTEX_SE2 379 -24.525479 -17.267300 -3.141187 +VERTEX_SE2 380 -24.512629 -18.256864 -1.599212 +VERTEX_SE2 381 -24.566147 -19.262700 -1.578642 +VERTEX_SE2 382 -24.588626 -20.261263 -1.565885 +VERTEX_SE2 383 -24.534225 -21.245665 -1.535988 +VERTEX_SE2 384 -23.513483 -21.170198 0.036982 +VERTEX_SE2 385 -22.532068 -21.134423 0.034131 +VERTEX_SE2 386 -21.536803 -21.071513 0.030462 +VERTEX_SE2 387 -20.541343 -21.033764 0.002015 +VERTEX_SE2 388 -20.515181 -20.064992 1.585595 +VERTEX_SE2 389 -20.523824 -19.062950 1.596379 +VERTEX_SE2 390 -20.567955 -18.063920 1.624528 +VERTEX_SE2 391 -20.639787 -17.063364 1.640482 +VERTEX_SE2 392 -19.638612 -17.009007 0.088572 +VERTEX_SE2 393 -18.661579 -16.908522 0.073611 +VERTEX_SE2 394 -17.650527 -16.862889 0.086874 +VERTEX_SE2 395 -16.643900 -16.749023 0.119479 +VERTEX_SE2 396 -16.563869 -17.748610 -1.484521 +VERTEX_SE2 397 -16.506150 -18.730496 -1.451631 +VERTEX_SE2 398 -16.400934 -19.717189 -1.450185 +VERTEX_SE2 399 -16.250621 -20.701499 -1.436124 +VERTEX_SE2 400 -17.257295 -20.861860 -2.965969 +VERTEX_SE2 401 -18.281253 -21.034208 -2.995446 +VERTEX_SE2 402 -19.270232 -21.213798 -3.045342 +VERTEX_SE2 403 -20.273761 -21.294293 -3.066614 +VERTEX_SE2 404 -19.252019 -21.230511 0.093951 +VERTEX_SE2 405 -18.249357 -21.130311 0.078253 +VERTEX_SE2 406 -17.242796 -21.063540 0.065657 +VERTEX_SE2 407 -16.273981 -20.986970 0.125016 +VERTEX_SE2 408 -16.166323 -21.968629 -1.454484 +VERTEX_SE2 409 -16.051970 -22.952596 -1.464246 +VERTEX_SE2 410 -15.965488 -23.954320 -1.453630 +VERTEX_SE2 411 -15.862792 -24.925893 -1.475304 +VERTEX_SE2 412 -14.866632 -24.855878 0.085156 +VERTEX_SE2 413 -13.887561 -24.782949 0.047605 +VERTEX_SE2 414 -12.919253 -24.740470 0.044602 +VERTEX_SE2 415 -11.902915 -24.711469 0.057920 +VERTEX_SE2 416 -12.906427 -24.763303 -3.090335 +VERTEX_SE2 417 -13.889706 -24.778492 -3.059711 +VERTEX_SE2 418 -14.907143 -24.842586 -3.079553 +VERTEX_SE2 419 -15.907588 -24.919359 -3.063574 +VERTEX_SE2 420 -15.795934 -25.961477 -1.495508 +VERTEX_SE2 421 -15.755292 -26.936471 -1.489215 +VERTEX_SE2 422 -15.655135 -27.883208 -1.465959 +VERTEX_SE2 423 -15.600638 -28.889500 -1.468330 +VERTEX_SE2 424 -15.491714 -29.862880 -1.476153 +VERTEX_SE2 425 -15.352215 -30.836493 -1.507650 +VERTEX_SE2 426 -15.328783 -31.805667 -1.563097 +VERTEX_SE2 427 -15.344649 -32.804233 -1.597524 +VERTEX_SE2 428 -14.317043 -32.827858 -0.058924 +VERTEX_SE2 429 -13.351153 -32.878846 -0.055885 +VERTEX_SE2 430 -12.323232 -32.930132 -0.068026 +VERTEX_SE2 431 -11.355891 -33.000970 -0.094753 +VERTEX_SE2 432 -11.422182 -33.962753 -1.704853 +VERTEX_SE2 433 -11.516198 -34.957761 -1.673174 +VERTEX_SE2 434 -11.598520 -35.952673 -1.710159 +VERTEX_SE2 435 -11.733078 -36.952505 -1.761329 +VERTEX_SE2 436 -12.700466 -36.723084 2.923271 +VERTEX_SE2 437 -13.621406 -36.531830 2.958488 +VERTEX_SE2 438 -14.594306 -36.344561 2.957429 +VERTEX_SE2 439 -15.541812 -36.186976 2.955908 +VERTEX_SE2 440 -15.718156 -37.167918 -1.723702 +VERTEX_SE2 441 -15.871391 -38.157322 -1.724457 +VERTEX_SE2 442 -15.999989 -39.151756 -1.738499 +VERTEX_SE2 443 -16.156187 -40.158478 -1.726976 +VERTEX_SE2 444 -16.031659 -39.214277 1.410664 +VERTEX_SE2 445 -15.872913 -38.220525 1.373073 +VERTEX_SE2 446 -15.692913 -37.219714 1.399598 +VERTEX_SE2 447 -15.516885 -36.257451 1.408124 +VERTEX_SE2 448 -14.544469 -36.420118 -0.143926 +VERTEX_SE2 449 -13.514937 -36.563765 -0.098476 +VERTEX_SE2 450 -12.513376 -36.634269 -0.131293 +VERTEX_SE2 451 -11.525185 -36.788418 -0.122379 +VERTEX_SE2 452 -12.538473 -36.630645 3.022801 +VERTEX_SE2 453 -13.544586 -36.509581 2.977890 +VERTEX_SE2 454 -14.547422 -36.369301 2.987333 +VERTEX_SE2 455 -15.534663 -36.210591 2.964093 +VERTEX_SE2 456 -14.548831 -36.446630 -0.197017 +VERTEX_SE2 457 -13.563113 -36.637853 -0.174448 +VERTEX_SE2 458 -12.577803 -36.816946 -0.176525 +VERTEX_SE2 459 -11.578778 -37.004975 -0.192017 +VERTEX_SE2 460 -12.562025 -36.799337 2.914953 +VERTEX_SE2 461 -13.524544 -36.546467 2.951072 +VERTEX_SE2 462 -14.557713 -36.363147 2.920094 +VERTEX_SE2 463 -15.529301 -36.135325 2.906741 +VERTEX_SE2 464 -15.773077 -37.085688 -1.780989 +VERTEX_SE2 465 -16.004031 -38.024493 -1.768021 +VERTEX_SE2 466 -16.169882 -39.032047 -1.765065 +VERTEX_SE2 467 -16.371472 -40.017080 -1.774109 +VERTEX_SE2 468 -17.344262 -39.830076 2.942641 +VERTEX_SE2 469 -18.342621 -39.636925 2.922596 +VERTEX_SE2 470 -19.278946 -39.453483 2.879746 +VERTEX_SE2 471 -20.232176 -39.176715 2.888304 +VERTEX_SE2 472 -19.278310 -39.419455 -0.245356 +VERTEX_SE2 473 -18.287128 -39.652646 -0.246529 +VERTEX_SE2 474 -17.302944 -39.933310 -0.267649 +VERTEX_SE2 475 -16.313875 -40.201461 -0.301872 +VERTEX_SE2 476 -17.278004 -39.875778 2.802528 +VERTEX_SE2 477 -18.225991 -39.565947 2.760923 +VERTEX_SE2 478 -19.185823 -39.213076 2.749839 +VERTEX_SE2 479 -20.109863 -38.844484 2.751358 +VERTEX_SE2 480 -19.172565 -39.240556 -0.378792 +VERTEX_SE2 481 -18.270851 -39.620114 -0.359533 +VERTEX_SE2 482 -17.343148 -39.962954 -0.371534 +VERTEX_SE2 483 -16.383077 -40.364979 -0.367851 +VERTEX_SE2 484 -15.982138 -39.417796 1.179919 +VERTEX_SE2 485 -15.573298 -38.441302 1.194467 +VERTEX_SE2 486 -15.231338 -37.523027 1.189482 +VERTEX_SE2 487 -14.851069 -36.571035 1.202137 +VERTEX_SE2 488 -13.965962 -36.888022 -0.380333 +VERTEX_SE2 489 -13.055709 -37.256383 -0.386233 +VERTEX_SE2 490 -12.112069 -37.633934 -0.384442 +VERTEX_SE2 491 -11.181565 -38.004466 -0.379850 +VERTEX_SE2 492 -11.593557 -38.907314 -1.940700 +VERTEX_SE2 493 -11.944114 -39.837782 -1.982513 +VERTEX_SE2 494 -12.331862 -40.721305 -2.009169 +VERTEX_SE2 495 -12.723771 -41.618661 -1.931193 +VERTEX_SE2 496 -12.355672 -40.724477 1.243377 +VERTEX_SE2 497 -11.994826 -39.810163 1.226540 +VERTEX_SE2 498 -11.641836 -38.900935 1.225442 +VERTEX_SE2 499 -11.264159 -37.965306 1.186233 +VERTEX_SE2 500 -11.625842 -38.890562 -1.971657 +VERTEX_SE2 501 -12.027053 -39.791291 -1.956832 +VERTEX_SE2 502 -12.405387 -40.699629 -1.952949 +VERTEX_SE2 503 -12.784968 -41.638125 -1.924388 +VERTEX_SE2 504 -12.442926 -40.724693 1.206002 +VERTEX_SE2 505 -12.118481 -39.841224 1.214238 +VERTEX_SE2 506 -11.780404 -38.900382 1.211050 +VERTEX_SE2 507 -11.387946 -37.993791 1.206467 +VERTEX_SE2 508 -10.472527 -38.331830 -0.318093 +VERTEX_SE2 509 -9.522322 -38.649338 -0.359219 +VERTEX_SE2 510 -8.562058 -39.020723 -0.310708 +VERTEX_SE2 511 -7.583446 -39.336381 -0.290264 +VERTEX_SE2 512 -7.882085 -40.302942 -1.891034 +VERTEX_SE2 513 -8.177093 -41.250105 -1.881586 +VERTEX_SE2 514 -8.496015 -42.235398 -1.899565 +VERTEX_SE2 515 -8.801324 -43.186508 -1.913033 +VERTEX_SE2 516 -8.448478 -42.265030 1.219617 +VERTEX_SE2 517 -8.096839 -41.370649 1.227727 +VERTEX_SE2 518 -7.775420 -40.394218 1.235166 +VERTEX_SE2 519 -7.461529 -39.393813 1.233849 +VERTEX_SE2 520 -8.379405 -39.050247 2.807339 +VERTEX_SE2 521 -9.326413 -38.768316 2.799136 +VERTEX_SE2 522 -10.263983 -38.400563 2.750438 +VERTEX_SE2 523 -11.205075 -38.000046 2.759175 +VERTEX_SE2 524 -10.322766 -38.411517 -0.374225 +VERTEX_SE2 525 -9.435027 -38.762841 -0.383937 +VERTEX_SE2 526 -8.488099 -39.122960 -0.368394 +VERTEX_SE2 527 -7.557784 -39.503370 -0.361689 +VERTEX_SE2 528 -8.503085 -39.127312 2.813951 +VERTEX_SE2 529 -9.446731 -38.793135 2.807536 +VERTEX_SE2 530 -10.398266 -38.443049 2.774319 +VERTEX_SE2 531 -11.373032 -38.087378 2.805190 +VERTEX_SE2 532 -11.651137 -39.054125 -1.916920 +VERTEX_SE2 533 -11.990623 -40.037194 -1.913912 +VERTEX_SE2 534 -12.312399 -40.981057 -1.900723 +VERTEX_SE2 535 -12.637557 -41.929582 -1.860552 +VERTEX_SE2 536 -12.365490 -40.973578 1.279938 +VERTEX_SE2 537 -12.071620 -40.014677 1.284284 +VERTEX_SE2 538 -11.809751 -39.100725 1.280327 +VERTEX_SE2 539 -11.496897 -38.148622 1.262864 +VERTEX_SE2 540 -11.847067 -39.098343 -1.871616 +VERTEX_SE2 541 -12.114078 -40.071968 -1.855251 +VERTEX_SE2 542 -12.359996 -41.056749 -1.849549 +VERTEX_SE2 543 -12.651912 -42.060314 -1.835846 +VERTEX_SE2 544 -11.703449 -42.297343 -0.265476 +VERTEX_SE2 545 -10.741992 -42.569615 -0.253905 +VERTEX_SE2 546 -9.824424 -42.879499 -0.227200 +VERTEX_SE2 547 -8.854910 -43.137927 -0.266540 +VERTEX_SE2 548 -8.600859 -42.139071 1.314830 +VERTEX_SE2 549 -8.349027 -41.202515 1.327088 +VERTEX_SE2 550 -8.136418 -40.201972 1.295567 +VERTEX_SE2 551 -7.849279 -39.227065 1.273321 +VERTEX_SE2 552 -8.795364 -38.941347 2.793171 +VERTEX_SE2 553 -9.736351 -38.636559 2.779113 +VERTEX_SE2 554 -10.653774 -38.266895 2.774998 +VERTEX_SE2 555 -11.625086 -37.896515 2.789486 +VERTEX_SE2 556 -10.694494 -38.191536 -0.356824 +VERTEX_SE2 557 -9.755804 -38.529155 -0.361482 +VERTEX_SE2 558 -8.787216 -38.892804 -0.360018 +VERTEX_SE2 559 -7.848543 -39.254109 -0.373779 +VERTEX_SE2 560 -7.472334 -38.334234 1.161601 +VERTEX_SE2 561 -7.123778 -37.454343 1.170501 +VERTEX_SE2 562 -6.715536 -36.487140 1.139640 +VERTEX_SE2 563 -6.280638 -35.610352 1.152417 +VERTEX_SE2 564 -5.872476 -34.719951 1.136643 +VERTEX_SE2 565 -5.482892 -33.785560 1.144349 +VERTEX_SE2 566 -5.100364 -32.863140 1.126255 +VERTEX_SE2 567 -4.689997 -31.959218 1.119126 +VERTEX_SE2 568 -5.126483 -32.897764 -2.035854 +VERTEX_SE2 569 -5.574944 -33.781672 -2.032463 +VERTEX_SE2 570 -6.025811 -34.700744 -1.999947 +VERTEX_SE2 571 -6.496816 -35.597245 -1.980605 +VERTEX_SE2 572 -5.552818 -36.017333 -0.470245 +VERTEX_SE2 573 -4.666295 -36.500518 -0.448332 +VERTEX_SE2 574 -3.769273 -36.905593 -0.459892 +VERTEX_SE2 575 -2.872366 -37.366989 -0.414149 +VERTEX_SE2 576 -2.480183 -36.462342 1.174831 +VERTEX_SE2 577 -2.106877 -35.529399 1.174019 +VERTEX_SE2 578 -1.721473 -34.635983 1.132685 +VERTEX_SE2 579 -1.306580 -33.712979 1.123206 +VERTEX_SE2 580 -2.208048 -33.266709 2.681816 +VERTEX_SE2 581 -3.067347 -32.837862 2.690900 +VERTEX_SE2 582 -3.970021 -32.443871 2.681780 +VERTEX_SE2 583 -4.864571 -31.975639 2.694322 +VERTEX_SE2 584 -5.299253 -32.843567 -2.009378 +VERTEX_SE2 585 -5.667037 -33.769982 -1.996750 +VERTEX_SE2 586 -6.049756 -34.669040 -2.002590 +VERTEX_SE2 587 -6.468071 -35.618522 -2.065828 +VERTEX_SE2 588 -7.343678 -35.132233 2.636522 +VERTEX_SE2 589 -8.226124 -34.640456 2.640381 +VERTEX_SE2 590 -9.134191 -34.167283 2.665791 +VERTEX_SE2 591 -10.022127 -33.714163 2.676376 +VERTEX_SE2 592 -9.555123 -32.834698 1.044206 +VERTEX_SE2 593 -9.088772 -31.968875 1.028615 +VERTEX_SE2 594 -8.555008 -31.121913 1.030347 +VERTEX_SE2 595 -8.030299 -30.260531 1.001244 +VERTEX_SE2 596 -7.189906 -30.775193 -0.586486 +VERTEX_SE2 597 -6.317895 -31.331210 -0.609886 +VERTEX_SE2 598 -5.479211 -31.896825 -0.599830 +VERTEX_SE2 599 -4.625364 -32.453524 -0.600302 +VERTEX_SE2 600 -5.162087 -33.266293 -2.133892 +VERTEX_SE2 601 -5.725012 -34.099762 -2.120714 +VERTEX_SE2 602 -6.266392 -34.956393 -2.120784 +VERTEX_SE2 603 -6.788586 -35.802024 -2.137657 +VERTEX_SE2 604 -5.913992 -36.313528 -0.572347 +VERTEX_SE2 605 -5.080970 -36.895103 -0.540521 +VERTEX_SE2 606 -4.237901 -37.399484 -0.492807 +VERTEX_SE2 607 -3.352015 -37.879121 -0.499614 +VERTEX_SE2 608 -2.880831 -36.974836 1.056636 +VERTEX_SE2 609 -2.412434 -36.087430 1.048950 +VERTEX_SE2 610 -1.932325 -35.207138 1.022455 +VERTEX_SE2 611 -1.416544 -34.361404 1.014187 +VERTEX_SE2 612 -1.931300 -35.202653 -2.167443 +VERTEX_SE2 613 -2.523237 -36.011439 -2.165609 +VERTEX_SE2 614 -3.127061 -36.883714 -2.187949 +VERTEX_SE2 615 -3.710716 -37.745399 -2.194393 +VERTEX_SE2 616 -3.116988 -36.926157 0.940227 +VERTEX_SE2 617 -2.526815 -36.128733 0.906346 +VERTEX_SE2 618 -1.914304 -35.364367 0.933991 +VERTEX_SE2 619 -1.355420 -34.576728 0.930293 +VERTEX_SE2 620 -0.547813 -35.122949 -0.597727 +VERTEX_SE2 621 0.309367 -35.665486 -0.622004 +VERTEX_SE2 622 1.173101 -36.243781 -0.642293 +VERTEX_SE2 623 1.958363 -36.864835 -0.654678 +VERTEX_SE2 624 1.179364 -36.226518 2.496972 +VERTEX_SE2 625 0.363132 -35.586468 2.496734 +VERTEX_SE2 626 -0.447260 -34.970022 2.533027 +VERTEX_SE2 627 -1.242844 -34.378327 2.521650 +VERTEX_SE2 628 -1.836070 -35.158829 -2.185300 +VERTEX_SE2 629 -2.401791 -35.992307 -2.158441 +VERTEX_SE2 630 -2.950628 -36.800673 -2.137630 +VERTEX_SE2 631 -3.474058 -37.643999 -2.109055 +VERTEX_SE2 632 -2.600058 -38.116170 -0.540595 +VERTEX_SE2 633 -1.778762 -38.644071 -0.522671 +VERTEX_SE2 634 -0.919798 -39.141322 -0.513951 +VERTEX_SE2 635 -0.093807 -39.601529 -0.554532 +VERTEX_SE2 636 -0.926303 -39.093174 2.568428 +VERTEX_SE2 637 -1.766964 -38.559769 2.555346 +VERTEX_SE2 638 -2.592559 -37.988821 2.570842 +VERTEX_SE2 639 -3.438483 -37.432854 2.589726 +VERTEX_SE2 640 -2.926621 -36.594388 1.024656 +VERTEX_SE2 641 -2.392505 -35.744659 1.002684 +VERTEX_SE2 642 -1.816524 -34.875395 1.009992 +VERTEX_SE2 643 -1.255281 -34.074453 1.017839 +VERTEX_SE2 644 -1.767834 -34.959901 -2.139101 +VERTEX_SE2 645 -2.330494 -35.782094 -2.136554 +VERTEX_SE2 646 -2.830173 -36.580794 -2.137475 +VERTEX_SE2 647 -3.377042 -37.416389 -2.145004 +VERTEX_SE2 648 -2.537989 -37.989474 -0.573544 +VERTEX_SE2 649 -1.711321 -38.554689 -0.566188 +VERTEX_SE2 650 -0.844104 -39.097569 -0.571509 +VERTEX_SE2 651 0.022135 -39.604904 -0.623085 +VERTEX_SE2 652 0.639401 -38.739328 0.966985 +VERTEX_SE2 653 1.179084 -37.952192 0.985732 +VERTEX_SE2 654 1.702001 -37.073989 0.942372 +VERTEX_SE2 655 2.278880 -36.301422 0.962533 +VERTEX_SE2 656 1.688944 -37.106586 -2.166507 +VERTEX_SE2 657 1.103061 -37.888508 -2.206723 +VERTEX_SE2 658 0.509181 -38.662548 -2.245170 +VERTEX_SE2 659 -0.104021 -39.450030 -2.206314 +VERTEX_SE2 660 0.709214 -40.073971 -0.627664 +VERTEX_SE2 661 1.511187 -40.653879 -0.651655 +VERTEX_SE2 662 2.304110 -41.248373 -0.624567 +VERTEX_SE2 663 3.064360 -41.810593 -0.625278 +VERTEX_SE2 664 2.483678 -42.630071 -2.235668 +VERTEX_SE2 665 1.850073 -43.440548 -2.220165 +VERTEX_SE2 666 1.215805 -44.217378 -2.206822 +VERTEX_SE2 667 0.623011 -45.005781 -2.224252 +VERTEX_SE2 668 1.212014 -44.237586 0.940988 +VERTEX_SE2 669 1.788139 -43.408302 0.954720 +VERTEX_SE2 670 2.367342 -42.592565 0.968789 +VERTEX_SE2 671 2.972004 -41.758714 0.955034 +VERTEX_SE2 672 2.397385 -42.561051 -2.172856 +VERTEX_SE2 673 1.824598 -43.402524 -2.123755 +VERTEX_SE2 674 1.312736 -44.251212 -2.117013 +VERTEX_SE2 675 0.816899 -45.084131 -2.099663 +VERTEX_SE2 676 1.328927 -44.211324 1.014487 +VERTEX_SE2 677 1.870959 -43.378957 1.018988 +VERTEX_SE2 678 2.381561 -42.538415 0.998636 +VERTEX_SE2 679 2.930362 -41.739811 1.021306 +VERTEX_SE2 680 2.076464 -41.223644 2.576676 +VERTEX_SE2 681 1.270176 -40.749608 2.602599 +VERTEX_SE2 682 0.384868 -40.226230 2.579341 +VERTEX_SE2 683 -0.461243 -39.709129 2.579332 +VERTEX_SE2 684 0.081179 -38.834721 1.001342 +VERTEX_SE2 685 0.618181 -37.978930 0.984669 +VERTEX_SE2 686 1.140573 -37.131954 0.991770 +VERTEX_SE2 687 1.668726 -36.299915 1.034230 +VERTEX_SE2 688 0.828789 -35.770930 2.570140 +VERTEX_SE2 689 0.008081 -35.252439 2.608635 +VERTEX_SE2 690 -0.856366 -34.726374 2.634103 +VERTEX_SE2 691 -1.717603 -34.258848 2.632403 +VERTEX_SE2 692 -1.258444 -33.391520 0.987363 +VERTEX_SE2 693 -0.733258 -32.537759 0.988963 +VERTEX_SE2 694 -0.202969 -31.698347 0.998719 +VERTEX_SE2 695 0.345544 -30.851219 1.020653 +VERTEX_SE2 696 1.184773 -31.358747 -0.568417 +VERTEX_SE2 697 2.034030 -31.924168 -0.553262 +VERTEX_SE2 698 2.850867 -32.480836 -0.539499 +VERTEX_SE2 699 3.671808 -33.023180 -0.525409 +VERTEX_SE2 700 4.207555 -32.140912 1.077261 +VERTEX_SE2 701 4.669137 -31.243385 1.056589 +VERTEX_SE2 702 5.147407 -30.380619 1.023677 +VERTEX_SE2 703 5.670224 -29.520500 1.027299 +VERTEX_SE2 704 4.804069 -28.988812 2.596149 +VERTEX_SE2 705 3.993792 -28.461381 2.579563 +VERTEX_SE2 706 3.122654 -27.894442 2.604577 +VERTEX_SE2 707 2.236569 -27.344275 2.598686 +VERTEX_SE2 708 1.706736 -28.189437 -2.103024 +VERTEX_SE2 709 1.223287 -29.048767 -2.072006 +VERTEX_SE2 710 0.764376 -29.943519 -2.083643 +VERTEX_SE2 711 0.296751 -30.842486 -2.125536 +VERTEX_SE2 712 -0.556390 -30.365453 2.574994 +VERTEX_SE2 713 -1.396987 -29.840667 2.574392 +VERTEX_SE2 714 -2.229459 -29.290722 2.562174 +VERTEX_SE2 715 -3.044701 -28.748229 2.563694 +VERTEX_SE2 716 -2.235948 -29.286475 -0.555756 +VERTEX_SE2 717 -1.389377 -29.801890 -0.553580 +VERTEX_SE2 718 -0.531026 -30.339319 -0.560711 +VERTEX_SE2 719 0.324808 -30.880594 -0.581537 +VERTEX_SE2 720 0.877320 -30.050158 0.971963 +VERTEX_SE2 721 1.451282 -29.234062 0.981853 +VERTEX_SE2 722 2.018271 -28.415217 0.988733 +VERTEX_SE2 723 2.601697 -27.580263 0.992642 +VERTEX_SE2 724 2.049034 -28.413988 -2.182818 +VERTEX_SE2 725 1.492846 -29.218834 -2.201940 +VERTEX_SE2 726 0.910535 -30.007597 -2.225846 +VERTEX_SE2 727 0.296877 -30.785236 -2.242642 +VERTEX_SE2 728 1.103326 -31.437988 -0.665792 +VERTEX_SE2 729 1.906034 -32.038309 -0.665936 +VERTEX_SE2 730 2.686217 -32.659304 -0.670586 +VERTEX_SE2 731 3.497915 -33.249990 -0.680218 +VERTEX_SE2 732 4.108243 -32.496915 0.855832 +VERTEX_SE2 733 4.777836 -31.759585 0.866580 +VERTEX_SE2 734 5.417963 -30.991670 0.828668 +VERTEX_SE2 735 6.078052 -30.231997 0.845094 +VERTEX_SE2 736 5.291033 -29.535612 2.432634 +VERTEX_SE2 737 4.473475 -28.916083 2.444251 +VERTEX_SE2 738 3.723104 -28.282895 2.455871 +VERTEX_SE2 739 2.931092 -27.635814 2.470986 +VERTEX_SE2 740 3.738360 -28.242369 -0.642564 +VERTEX_SE2 741 4.560195 -28.811010 -0.611976 +VERTEX_SE2 742 5.402338 -29.347778 -0.596267 +VERTEX_SE2 743 6.226961 -29.907574 -0.586497 +VERTEX_SE2 744 5.688237 -30.758982 -2.177367 +VERTEX_SE2 745 5.139267 -31.578159 -2.177226 +VERTEX_SE2 746 4.576770 -32.434788 -2.176318 +VERTEX_SE2 747 4.011540 -33.241054 -2.181777 +VERTEX_SE2 748 4.573021 -32.409218 0.946563 +VERTEX_SE2 749 5.158317 -31.558555 0.923623 +VERTEX_SE2 750 5.706236 -30.717631 0.920342 +VERTEX_SE2 751 6.300399 -29.923305 0.926394 +VERTEX_SE2 752 5.689101 -30.668821 -2.206156 +VERTEX_SE2 753 5.075405 -31.433051 -2.205196 +VERTEX_SE2 754 4.472027 -32.218237 -2.249977 +VERTEX_SE2 755 3.900034 -33.005673 -2.297032 +VERTEX_SE2 756 4.616866 -33.638787 -0.743392 +VERTEX_SE2 757 5.357072 -34.333313 -0.753741 +VERTEX_SE2 758 6.073310 -35.006912 -0.744131 +VERTEX_SE2 759 6.816001 -35.616124 -0.709929 +VERTEX_SE2 760 7.480641 -34.891981 0.877891 +VERTEX_SE2 761 8.125527 -34.166158 0.878600 +VERTEX_SE2 762 8.784111 -33.407224 0.883655 +VERTEX_SE2 763 9.453682 -32.641333 0.879972 +VERTEX_SE2 764 8.805980 -33.399598 -2.266948 +VERTEX_SE2 765 8.157519 -34.193914 -2.263184 +VERTEX_SE2 766 7.514151 -34.982442 -2.250454 +VERTEX_SE2 767 6.865872 -35.745734 -2.245437 +VERTEX_SE2 768 6.259911 -36.532839 -2.273318 +VERTEX_SE2 769 5.587321 -37.282589 -2.300476 +VERTEX_SE2 770 4.944853 -38.030748 -2.286059 +VERTEX_SE2 771 4.299965 -38.817112 -2.280448 +VERTEX_SE2 772 3.535376 -38.144288 2.415632 +VERTEX_SE2 773 2.803015 -37.535649 2.432232 +VERTEX_SE2 774 2.069254 -36.884651 2.430012 +VERTEX_SE2 775 1.312221 -36.222714 2.456752 +VERTEX_SE2 776 1.948867 -35.448880 0.930182 +VERTEX_SE2 777 2.558657 -34.654665 0.960941 +VERTEX_SE2 778 3.101784 -33.848915 0.947476 +VERTEX_SE2 779 3.709926 -33.047929 0.921191 +VERTEX_SE2 780 4.504730 -33.609201 -0.650539 +VERTEX_SE2 781 5.352346 -34.173458 -0.681454 +VERTEX_SE2 782 6.129290 -34.814887 -0.667074 +VERTEX_SE2 783 6.912269 -35.472282 -0.689795 +VERTEX_SE2 784 6.259588 -36.244793 -2.229535 +VERTEX_SE2 785 5.629833 -37.015912 -2.236031 +VERTEX_SE2 786 5.054946 -37.849667 -2.245061 +VERTEX_SE2 787 4.379626 -38.575510 -2.240955 +VERTEX_SE2 788 5.156719 -39.226496 -0.680425 +VERTEX_SE2 789 5.923708 -39.828359 -0.699497 +VERTEX_SE2 790 6.665841 -40.495716 -0.713357 +VERTEX_SE2 791 7.422742 -41.140337 -0.691891 +VERTEX_SE2 792 6.834139 -41.857006 -2.273191 +VERTEX_SE2 793 6.204299 -42.646100 -2.284736 +VERTEX_SE2 794 5.547752 -43.426878 -2.293419 +VERTEX_SE2 795 4.928067 -44.210248 -2.251243 +VERTEX_SE2 796 5.716590 -44.822064 -0.654553 +VERTEX_SE2 797 6.517524 -45.422573 -0.628709 +VERTEX_SE2 798 7.339229 -46.039381 -0.660093 +VERTEX_SE2 799 8.115286 -46.652178 -0.691719 +VERTEX_SE2 800 7.452538 -47.464770 -2.261719 +VERTEX_SE2 801 6.822392 -48.256782 -2.276967 +VERTEX_SE2 802 6.159308 -49.030071 -2.231174 +VERTEX_SE2 803 5.580453 -49.819015 -2.215399 +VERTEX_SE2 804 6.378686 -50.427707 -0.663609 +VERTEX_SE2 805 7.129370 -51.060927 -0.637996 +VERTEX_SE2 806 7.950881 -51.666611 -0.634203 +VERTEX_SE2 807 8.782780 -52.275012 -0.638647 +VERTEX_SE2 808 8.203845 -53.104591 -2.188667 +VERTEX_SE2 809 7.594298 -53.906625 -2.187151 +VERTEX_SE2 810 7.044007 -54.717403 -2.186172 +VERTEX_SE2 811 6.445068 -55.550980 -2.191418 +VERTEX_SE2 812 7.235637 -56.103716 -0.612928 +VERTEX_SE2 813 8.077975 -56.711758 -0.606517 +VERTEX_SE2 814 8.882474 -57.281330 -0.629759 +VERTEX_SE2 815 9.727432 -57.873215 -0.618600 +VERTEX_SE2 816 10.258260 -57.088781 0.911680 +VERTEX_SE2 817 10.845434 -56.280996 0.953537 +VERTEX_SE2 818 11.414578 -55.486486 0.958574 +VERTEX_SE2 819 12.020297 -54.645573 0.958365 +VERTEX_SE2 820 11.417050 -55.422974 -2.188335 +VERTEX_SE2 821 10.849421 -56.234378 -2.198184 +VERTEX_SE2 822 10.255564 -57.021430 -2.180847 +VERTEX_SE2 823 9.676259 -57.829569 -2.151057 +VERTEX_SE2 824 8.820689 -57.279630 2.540363 +VERTEX_SE2 825 8.045319 -56.691011 2.531934 +VERTEX_SE2 826 7.181462 -56.116003 2.514191 +VERTEX_SE2 827 6.345659 -55.526011 2.497920 +VERTEX_SE2 828 5.583047 -54.951069 2.510214 +VERTEX_SE2 829 4.772178 -54.371957 2.511532 +VERTEX_SE2 830 3.997511 -53.796660 2.481208 +VERTEX_SE2 831 3.214692 -53.211419 2.508272 +VERTEX_SE2 832 4.004468 -53.848631 -0.626588 +VERTEX_SE2 833 4.826180 -54.461790 -0.626736 +VERTEX_SE2 834 5.628352 -55.030392 -0.695315 +VERTEX_SE2 835 6.365003 -55.640176 -0.732868 +VERTEX_SE2 836 7.022326 -54.906827 0.814272 +VERTEX_SE2 837 7.721840 -54.178215 0.804144 +VERTEX_SE2 838 8.441418 -53.471950 0.744079 +VERTEX_SE2 839 9.178933 -52.772149 0.714089 +VERTEX_SE2 840 9.852724 -53.564689 -0.869891 +VERTEX_SE2 841 10.499839 -54.340289 -0.839061 +VERTEX_SE2 842 11.145074 -55.077774 -0.837908 +VERTEX_SE2 843 11.800792 -55.845922 -0.832970 +VERTEX_SE2 844 12.532195 -55.139820 0.710190 +VERTEX_SE2 845 13.265901 -54.519111 0.704986 +VERTEX_SE2 846 14.037763 -53.829918 0.705305 +VERTEX_SE2 847 14.801605 -53.170265 0.733345 +VERTEX_SE2 848 14.024054 -53.835823 -2.361415 +VERTEX_SE2 849 13.283186 -54.501306 -2.410382 +VERTEX_SE2 850 12.521853 -55.163027 -2.389822 +VERTEX_SE2 851 11.813713 -55.854161 -2.356033 +VERTEX_SE2 852 11.113339 -56.549117 -2.337214 +VERTEX_SE2 853 10.413998 -57.293365 -2.298409 +VERTEX_SE2 854 9.751127 -58.081674 -2.318401 +VERTEX_SE2 855 9.072071 -58.811430 -2.286099 +VERTEX_SE2 856 8.325176 -58.224178 2.448131 +VERTEX_SE2 857 7.552466 -57.587470 2.458054 +VERTEX_SE2 858 6.784577 -56.990957 2.431080 +VERTEX_SE2 859 6.028538 -56.335166 2.472016 +VERTEX_SE2 860 6.799202 -56.925666 -0.633174 +VERTEX_SE2 861 7.539566 -57.515580 -0.596745 +VERTEX_SE2 862 8.329443 -58.084438 -0.611964 +VERTEX_SE2 863 9.157070 -58.664862 -0.604607 +VERTEX_SE2 864 8.308673 -58.114825 2.516003 +VERTEX_SE2 865 7.507464 -57.541675 2.490586 +VERTEX_SE2 866 6.700311 -56.945308 2.480130 +VERTEX_SE2 867 5.911033 -56.352534 2.504240 +VERTEX_SE2 868 6.718882 -56.968768 -0.617800 +VERTEX_SE2 869 7.528033 -57.536253 -0.560515 +VERTEX_SE2 870 8.405336 -58.077616 -0.534260 +VERTEX_SE2 871 9.236314 -58.601788 -0.543628 +VERTEX_SE2 872 10.105870 -59.125798 -0.559661 +VERTEX_SE2 873 10.921980 -59.637956 -0.594847 +VERTEX_SE2 874 11.745025 -60.242268 -0.583962 +VERTEX_SE2 875 12.591973 -60.785776 -0.571181 +VERTEX_SE2 876 13.136908 -59.948794 0.965489 +VERTEX_SE2 877 13.712451 -59.135202 0.951440 +VERTEX_SE2 878 14.307910 -58.318785 0.954326 +VERTEX_SE2 879 14.884922 -57.495773 0.940550 +VERTEX_SE2 880 14.303001 -58.323504 -2.204700 +VERTEX_SE2 881 13.723793 -59.155923 -2.220962 +VERTEX_SE2 882 13.108358 -59.934483 -2.239730 +VERTEX_SE2 883 12.462306 -60.712244 -2.265841 +VERTEX_SE2 884 13.082825 -59.952986 0.882089 +VERTEX_SE2 885 13.680365 -59.187080 0.865211 +VERTEX_SE2 886 14.343557 -58.418663 0.824746 +VERTEX_SE2 887 15.008297 -57.661772 0.854782 +VERTEX_SE2 888 15.746474 -58.322084 -0.690058 +VERTEX_SE2 889 16.512888 -58.977088 -0.674826 +VERTEX_SE2 890 17.319729 -59.636501 -0.641427 +VERTEX_SE2 891 18.108667 -60.247308 -0.643966 +VERTEX_SE2 892 17.299139 -59.636031 2.505424 +VERTEX_SE2 893 16.491883 -59.065028 2.578335 +VERTEX_SE2 894 15.646858 -58.546470 2.619377 +VERTEX_SE2 895 14.783883 -58.017751 2.613139 +VERTEX_SE2 896 15.313858 -57.153407 1.053309 +VERTEX_SE2 897 15.800121 -56.269978 1.008642 +VERTEX_SE2 898 16.324073 -55.403154 1.017855 +VERTEX_SE2 899 16.866255 -54.560799 1.010388 +VERTEX_SE2 900 16.299236 -55.401317 -2.136782 +VERTEX_SE2 901 15.781103 -56.239339 -2.190434 +VERTEX_SE2 902 15.144318 -57.024245 -2.247980 +VERTEX_SE2 903 14.536419 -57.796959 -2.243982 +VERTEX_SE2 904 15.331039 -58.417067 -0.697892 +VERTEX_SE2 905 16.117760 -59.027201 -0.699094 +VERTEX_SE2 906 16.894197 -59.672376 -0.718741 +VERTEX_SE2 907 17.647506 -60.304847 -0.730273 +VERTEX_SE2 908 18.296573 -59.562931 0.822397 +VERTEX_SE2 909 18.944223 -58.830311 0.863013 +VERTEX_SE2 910 19.601300 -58.100754 0.854544 +VERTEX_SE2 911 20.286042 -57.308461 0.837728 +VERTEX_SE2 912 19.621167 -58.019724 -2.307982 +VERTEX_SE2 913 18.943758 -58.763901 -2.296053 +VERTEX_SE2 914 18.314471 -59.526758 -2.283423 +VERTEX_SE2 915 17.662168 -60.307729 -2.262018 +VERTEX_SE2 916 18.411979 -60.946135 -0.703938 +VERTEX_SE2 917 19.160569 -61.584026 -0.743453 +VERTEX_SE2 918 19.883025 -62.254278 -0.763822 +VERTEX_SE2 919 20.611998 -62.949040 -0.776483 +VERTEX_SE2 920 19.929029 -62.253189 2.375517 +VERTEX_SE2 921 19.205054 -61.572850 2.359043 +VERTEX_SE2 922 18.495547 -60.869721 2.354901 +VERTEX_SE2 923 17.793709 -60.142415 2.335256 +VERTEX_SE2 924 18.488813 -60.870092 -0.853864 +VERTEX_SE2 925 19.120570 -61.602085 -0.817665 +VERTEX_SE2 926 19.781937 -62.332646 -0.864494 +VERTEX_SE2 927 20.431082 -63.085052 -0.847215 +VERTEX_SE2 928 19.697946 -63.785517 -2.400525 +VERTEX_SE2 929 18.971084 -64.459385 -2.389781 +VERTEX_SE2 930 18.286561 -65.168166 -2.382223 +VERTEX_SE2 931 17.571347 -65.909652 -2.382041 +VERTEX_SE2 932 18.281896 -66.674821 -0.807221 +VERTEX_SE2 933 18.980868 -67.376948 -0.765607 +VERTEX_SE2 934 19.744439 -68.027670 -0.765546 +VERTEX_SE2 935 20.481839 -68.708751 -0.736290 +VERTEX_SE2 936 19.700539 -68.058124 2.386940 +VERTEX_SE2 937 18.979265 -67.403692 2.403338 +VERTEX_SE2 938 18.227050 -66.699071 2.427572 +VERTEX_SE2 939 17.489184 -66.034688 2.397789 +VERTEX_SE2 940 16.745116 -65.326023 2.326677 +VERTEX_SE2 941 16.045039 -64.591750 2.323615 +VERTEX_SE2 942 15.379225 -63.903574 2.303477 +VERTEX_SE2 943 14.720641 -63.131111 2.284609 +VERTEX_SE2 944 15.470228 -62.457771 0.721669 +VERTEX_SE2 945 16.245307 -61.826174 0.703095 +VERTEX_SE2 946 17.015921 -61.179233 0.690316 +VERTEX_SE2 947 17.743997 -60.556433 0.673258 +VERTEX_SE2 948 18.410036 -61.308140 -0.880922 +VERTEX_SE2 949 19.012904 -62.115348 -0.895663 +VERTEX_SE2 950 19.599334 -62.911311 -0.886802 +VERTEX_SE2 951 20.223047 -63.661665 -0.883080 +VERTEX_SE2 952 19.587374 -62.877864 2.265300 +VERTEX_SE2 953 18.961513 -62.104467 2.272572 +VERTEX_SE2 954 18.317600 -61.292331 2.258046 +VERTEX_SE2 955 17.674530 -60.528607 2.261994 +VERTEX_SE2 956 16.891176 -61.155829 -2.450376 +VERTEX_SE2 957 16.068881 -61.788913 -2.444051 +VERTEX_SE2 958 15.281439 -62.451520 -2.443624 +VERTEX_SE2 959 14.502043 -63.101140 -2.429800 +VERTEX_SE2 960 15.243474 -62.418991 0.687290 +VERTEX_SE2 961 16.003325 -61.746656 0.676426 +VERTEX_SE2 962 16.777172 -61.116131 0.654064 +VERTEX_SE2 963 17.594225 -60.479443 0.666765 +VERTEX_SE2 964 16.828017 -61.089086 -2.514385 +VERTEX_SE2 965 16.040221 -61.656277 -2.500925 +VERTEX_SE2 966 15.218007 -62.272630 -2.504794 +VERTEX_SE2 967 14.408173 -62.873935 -2.525938 +VERTEX_SE2 968 15.226720 -62.293942 0.644112 +VERTEX_SE2 969 16.064894 -61.670570 0.643112 +VERTEX_SE2 970 16.854694 -61.071350 0.603821 +VERTEX_SE2 971 17.703705 -60.514476 0.586989 +VERTEX_SE2 972 17.172133 -59.683886 2.149029 +VERTEX_SE2 973 16.643433 -58.834547 2.156976 +VERTEX_SE2 974 16.113084 -58.032425 2.141879 +VERTEX_SE2 975 15.579137 -57.206429 2.170235 +VERTEX_SE2 976 15.047342 -56.416123 2.179068 +VERTEX_SE2 977 14.503449 -55.558079 2.169024 +VERTEX_SE2 978 13.920868 -54.786418 2.176893 +VERTEX_SE2 979 13.402556 -53.929090 2.187798 +VERTEX_SE2 980 14.004383 -54.758607 -0.928362 +VERTEX_SE2 981 14.643749 -55.539940 -0.935666 +VERTEX_SE2 982 15.213349 -56.336153 -0.957642 +VERTEX_SE2 983 15.786853 -57.139720 -0.930207 +VERTEX_SE2 984 15.203143 -56.320762 2.224233 +VERTEX_SE2 985 14.615267 -55.545851 2.196869 +VERTEX_SE2 986 14.043494 -54.754945 2.235081 +VERTEX_SE2 987 13.424786 -53.982704 2.242957 +VERTEX_SE2 988 14.197743 -53.379307 0.663387 +VERTEX_SE2 989 15.007738 -52.775568 0.660604 +VERTEX_SE2 990 15.823282 -52.155519 0.697591 +VERTEX_SE2 991 16.633900 -51.521807 0.677042 +VERTEX_SE2 992 17.276359 -52.305515 -0.852078 +VERTEX_SE2 993 17.970629 -53.090898 -0.848508 +VERTEX_SE2 994 18.631231 -53.802791 -0.837799 +VERTEX_SE2 995 19.281286 -54.539198 -0.787490 +VERTEX_SE2 996 20.015059 -53.860068 0.754790 +VERTEX_SE2 997 20.726773 -53.151060 0.761324 +VERTEX_SE2 998 21.445126 -52.472070 0.737015 +VERTEX_SE2 999 22.246628 -51.799033 0.768267 +VERTEX_SE2 1000 21.508498 -52.486809 -2.376593 +VERTEX_SE2 1001 20.799266 -53.186313 -2.355749 +VERTEX_SE2 1002 20.087816 -53.910666 -2.412360 +VERTEX_SE2 1003 19.297757 -54.612206 -2.422574 +VERTEX_SE2 1004 18.661575 -53.908645 2.333446 +VERTEX_SE2 1005 17.966511 -53.156063 2.372170 +VERTEX_SE2 1006 17.243526 -52.474354 2.379375 +VERTEX_SE2 1007 16.515708 -51.750611 2.375760 +VERTEX_SE2 1008 17.189175 -51.057637 0.781940 +VERTEX_SE2 1009 17.905408 -50.358520 0.774851 +VERTEX_SE2 1010 18.634648 -49.656343 0.782637 +VERTEX_SE2 1011 19.386237 -48.931590 0.784301 +VERTEX_SE2 1012 18.661648 -48.227503 2.327961 +VERTEX_SE2 1013 17.981494 -47.500555 2.365430 +VERTEX_SE2 1014 17.306133 -46.732115 2.374559 +VERTEX_SE2 1015 16.585903 -46.040372 2.374959 +VERTEX_SE2 1016 17.261022 -45.360262 0.791889 +VERTEX_SE2 1017 17.960261 -44.670392 0.794566 +VERTEX_SE2 1018 18.649787 -43.939855 0.779683 +VERTEX_SE2 1019 19.331441 -43.244713 0.808877 +VERTEX_SE2 1020 18.668819 -43.981791 -2.352293 +VERTEX_SE2 1021 17.959973 -44.681843 -2.365601 +VERTEX_SE2 1022 17.249844 -45.362382 -2.364926 +VERTEX_SE2 1023 16.559746 -46.029578 -2.330193 +VERTEX_SE2 1024 17.241362 -45.353747 0.815187 +VERTEX_SE2 1025 17.944770 -44.655590 0.806821 +VERTEX_SE2 1026 18.634306 -43.892722 0.801312 +VERTEX_SE2 1027 19.339248 -43.191012 0.749874 +VERTEX_SE2 1028 19.989421 -43.897757 -0.790486 +VERTEX_SE2 1029 20.655272 -44.621176 -0.781148 +VERTEX_SE2 1030 21.346939 -45.291160 -0.742256 +VERTEX_SE2 1031 22.091496 -45.970338 -0.739219 +VERTEX_SE2 1032 22.763307 -45.226688 0.837691 +VERTEX_SE2 1033 23.426232 -44.478058 0.841752 +VERTEX_SE2 1034 24.088169 -43.721907 0.847887 +VERTEX_SE2 1035 24.736379 -43.001317 0.874141 +VERTEX_SE2 1036 23.940396 -42.370329 2.489361 +VERTEX_SE2 1037 23.130619 -41.824038 2.491868 +VERTEX_SE2 1038 22.328959 -41.226800 2.465035 +VERTEX_SE2 1039 21.560391 -40.606048 2.462911 +VERTEX_SE2 1040 20.947012 -41.401756 -2.268039 +VERTEX_SE2 1041 20.313199 -42.184515 -2.239829 +VERTEX_SE2 1042 19.698446 -42.955637 -2.259353 +VERTEX_SE2 1043 19.049375 -43.716622 -2.286925 +VERTEX_SE2 1044 18.390864 -44.439649 -2.273956 +VERTEX_SE2 1045 17.738321 -45.171806 -2.270852 +VERTEX_SE2 1046 17.114928 -45.967044 -2.246605 +VERTEX_SE2 1047 16.492267 -46.740042 -2.224537 +VERTEX_SE2 1048 17.255506 -47.337353 -0.627497 +VERTEX_SE2 1049 18.096614 -47.954354 -0.670308 +VERTEX_SE2 1050 18.887078 -48.590897 -0.696876 +VERTEX_SE2 1051 19.677285 -49.282767 -0.650161 +VERTEX_SE2 1052 19.082101 -50.073312 -2.265961 +VERTEX_SE2 1053 18.462086 -50.819935 -2.277986 +VERTEX_SE2 1054 17.823298 -51.584354 -2.271956 +VERTEX_SE2 1055 17.207849 -52.308844 -2.217770 +VERTEX_SE2 1056 17.844423 -51.478502 0.910380 +VERTEX_SE2 1057 18.455718 -50.738261 0.931035 +VERTEX_SE2 1058 19.038318 -49.923783 0.953148 +VERTEX_SE2 1059 19.636721 -49.125863 0.917888 +VERTEX_SE2 1060 19.058620 -49.928730 -2.219862 +VERTEX_SE2 1061 18.442564 -50.715424 -2.213634 +VERTEX_SE2 1062 17.825702 -51.504020 -2.274391 +VERTEX_SE2 1063 17.204093 -52.248112 -2.221611 +VERTEX_SE2 1064 18.020167 -52.849495 -0.683221 +VERTEX_SE2 1065 18.802240 -53.476428 -0.699512 +VERTEX_SE2 1066 19.521388 -54.145957 -0.693211 +VERTEX_SE2 1067 20.287201 -54.800106 -0.718426 +VERTEX_SE2 1068 19.525872 -54.111153 2.435564 +VERTEX_SE2 1069 18.781820 -53.451638 2.458021 +VERTEX_SE2 1070 18.029184 -52.841016 2.426136 +VERTEX_SE2 1071 17.269164 -52.160440 2.418826 +VERTEX_SE2 1072 18.085385 -52.820950 -0.700434 +VERTEX_SE2 1073 18.856385 -53.425488 -0.722454 +VERTEX_SE2 1074 19.586050 -54.125287 -0.705634 +VERTEX_SE2 1075 20.334140 -54.789979 -0.703964 +VERTEX_SE2 1076 19.547456 -54.138950 2.400606 +VERTEX_SE2 1077 18.779258 -53.434255 2.378617 +VERTEX_SE2 1078 18.036441 -52.763669 2.374526 +VERTEX_SE2 1079 17.307366 -52.055277 2.359871 +VERTEX_SE2 1080 18.014297 -52.775657 -0.818379 +VERTEX_SE2 1081 18.684968 -53.515493 -0.830095 +VERTEX_SE2 1082 19.385883 -54.212249 -0.853470 +VERTEX_SE2 1083 20.047463 -54.968806 -0.847829 +VERTEX_SE2 1084 19.319156 -55.634261 -2.478499 +VERTEX_SE2 1085 18.503638 -56.205991 -2.471483 +VERTEX_SE2 1086 17.690383 -56.826319 -2.436167 +VERTEX_SE2 1087 16.895006 -57.503246 -2.425344 +VERTEX_SE2 1088 17.638038 -56.865493 0.698076 +VERTEX_SE2 1089 18.403695 -56.197755 0.689458 +VERTEX_SE2 1090 19.123702 -55.523189 0.713264 +VERTEX_SE2 1091 19.849115 -54.864536 0.723588 +VERTEX_SE2 1092 19.097731 -55.510121 -2.425242 +VERTEX_SE2 1093 18.369793 -56.157497 -2.389037 +VERTEX_SE2 1094 17.601030 -56.872334 -2.356860 +VERTEX_SE2 1095 16.892707 -57.571522 -2.345109 +VERTEX_SE2 1096 17.579982 -56.849600 0.805821 +VERTEX_SE2 1097 18.229219 -56.185681 0.787621 +VERTEX_SE2 1098 18.931134 -55.500357 0.784740 +VERTEX_SE2 1099 19.641889 -54.792148 0.780129 +VERTEX_SE2 1100 20.361608 -55.518940 -0.710271 +VERTEX_SE2 1101 21.169251 -56.131138 -0.660678 +VERTEX_SE2 1102 21.977494 -56.771745 -0.681920 +VERTEX_SE2 1103 22.741924 -57.383509 -0.676823 +VERTEX_SE2 1104 22.083300 -58.198836 -2.296783 +VERTEX_SE2 1105 21.419095 -58.989457 -2.291922 +VERTEX_SE2 1106 20.770401 -59.731360 -2.304945 +VERTEX_SE2 1107 20.101995 -60.487175 -2.295044 +VERTEX_SE2 1108 19.373606 -59.872030 2.347416 +VERTEX_SE2 1109 18.665640 -59.147222 2.362618 +VERTEX_SE2 1110 17.986343 -58.463776 2.340524 +VERTEX_SE2 1111 17.283689 -57.778991 2.281879 +VERTEX_SE2 1112 16.557499 -58.466529 -2.413821 +VERTEX_SE2 1113 15.845247 -59.168323 -2.412674 +VERTEX_SE2 1114 15.131247 -59.827704 -2.396027 +VERTEX_SE2 1115 14.396980 -60.486555 -2.410752 +VERTEX_SE2 1116 15.078817 -61.242473 -0.861882 +VERTEX_SE2 1117 15.733752 -62.005342 -0.893071 +VERTEX_SE2 1118 16.377205 -62.768317 -0.890055 +VERTEX_SE2 1119 17.018151 -63.548479 -0.879076 +VERTEX_SE2 1120 16.390411 -62.724823 2.221034 +VERTEX_SE2 1121 15.822933 -61.958375 2.258972 +VERTEX_SE2 1122 15.209941 -61.222540 2.280825 +VERTEX_SE2 1123 14.523747 -60.465823 2.314184 +VERTEX_SE2 1124 15.294207 -59.789461 0.732734 +VERTEX_SE2 1125 16.025677 -59.116509 0.739409 +VERTEX_SE2 1126 16.754527 -58.467680 0.748844 +VERTEX_SE2 1127 17.522344 -57.735735 0.775692 +VERTEX_SE2 1128 18.272071 -57.064519 0.761492 +VERTEX_SE2 1129 18.985827 -56.361828 0.730763 +VERTEX_SE2 1130 19.756841 -55.670765 0.741002 +VERTEX_SE2 1131 20.494207 -55.001692 0.773964 +VERTEX_SE2 1132 19.779465 -55.706646 -2.400296 +VERTEX_SE2 1133 19.069213 -56.393011 -2.422462 +VERTEX_SE2 1134 18.302651 -57.049614 -2.454110 +VERTEX_SE2 1135 17.530086 -57.720084 -2.456103 +VERTEX_SE2 1136 18.238705 -57.106329 0.706847 +VERTEX_SE2 1137 19.003627 -56.491362 0.709255 +VERTEX_SE2 1138 19.754569 -55.844059 0.723125 +VERTEX_SE2 1139 20.490351 -55.187709 0.740420 +VERTEX_SE2 1140 19.749410 -55.906891 -2.375280 +VERTEX_SE2 1141 19.039234 -56.582208 -2.418764 +VERTEX_SE2 1142 18.291249 -57.274970 -2.428541 +VERTEX_SE2 1143 17.518434 -57.935613 -2.446900 +VERTEX_SE2 1144 18.295567 -57.294876 0.668180 +VERTEX_SE2 1145 19.052208 -56.674499 0.656809 +VERTEX_SE2 1146 19.883350 -56.045698 0.627675 +VERTEX_SE2 1147 20.709409 -55.490682 0.640558 +VERTEX_SE2 1148 20.110692 -54.690737 2.193408 +VERTEX_SE2 1149 19.574979 -53.867770 2.182779 +VERTEX_SE2 1150 18.986849 -53.034348 2.169155 +VERTEX_SE2 1151 18.386951 -52.225082 2.172807 +VERTEX_SE2 1152 17.539661 -52.778489 -2.588793 +VERTEX_SE2 1153 16.702631 -53.333439 -2.546685 +VERTEX_SE2 1154 15.902340 -53.895272 -2.525336 +VERTEX_SE2 1155 15.095987 -54.450296 -2.538042 +VERTEX_SE2 1156 15.676767 -55.252620 -0.940722 +VERTEX_SE2 1157 16.260736 -56.080054 -0.969116 +VERTEX_SE2 1158 16.798488 -56.861209 -0.924823 +VERTEX_SE2 1159 17.410099 -57.629960 -0.890854 +VERTEX_SE2 1160 16.796857 -56.841278 2.233646 +VERTEX_SE2 1161 16.174837 -56.078149 2.237451 +VERTEX_SE2 1162 15.572053 -55.325456 2.242682 +VERTEX_SE2 1163 14.928634 -54.540283 2.238736 +VERTEX_SE2 1164 14.330378 -53.777710 2.261753 +VERTEX_SE2 1165 13.668701 -52.988674 2.288562 +VERTEX_SE2 1166 13.020196 -52.269763 2.339352 +VERTEX_SE2 1167 12.332180 -51.492562 2.319699 +VERTEX_SE2 1168 12.990815 -52.245949 -0.820451 +VERTEX_SE2 1169 13.692861 -52.944630 -0.860371 +VERTEX_SE2 1170 14.367626 -53.678980 -0.823124 +VERTEX_SE2 1171 14.984005 -54.406764 -0.824403 +VERTEX_SE2 1172 14.313375 -53.687570 2.327077 +VERTEX_SE2 1173 13.644876 -52.980779 2.370228 +VERTEX_SE2 1174 12.941379 -52.289567 2.361568 +VERTEX_SE2 1175 12.244620 -51.550225 2.330596 +VERTEX_SE2 1176 11.577341 -52.250388 -2.357324 +VERTEX_SE2 1177 10.858088 -52.958773 -2.383597 +VERTEX_SE2 1178 10.133864 -53.687444 -2.363694 +VERTEX_SE2 1179 9.426292 -54.440642 -2.343448 +VERTEX_SE2 1180 8.717894 -53.728483 2.361532 +VERTEX_SE2 1181 8.010177 -53.045526 2.373253 +VERTEX_SE2 1182 7.271738 -52.348527 2.342728 +VERTEX_SE2 1183 6.593093 -51.655864 2.320869 +VERTEX_SE2 1184 7.231783 -52.389268 -0.801381 +VERTEX_SE2 1185 7.905199 -53.090713 -0.825241 +VERTEX_SE2 1186 8.628446 -53.890910 -0.845733 +VERTEX_SE2 1187 9.316039 -54.641414 -0.828297 +VERTEX_SE2 1188 10.094565 -53.965883 0.746303 +VERTEX_SE2 1189 10.814976 -53.274681 0.738204 +VERTEX_SE2 1190 11.582386 -52.578529 0.709516 +VERTEX_SE2 1191 12.321228 -51.948747 0.685991 +VERTEX_SE2 1192 11.708131 -51.173971 2.257941 +VERTEX_SE2 1193 11.057279 -50.368428 2.257209 +VERTEX_SE2 1194 10.405135 -49.574279 2.261468 +VERTEX_SE2 1195 9.749654 -48.804834 2.267709 +VERTEX_SE2 1196 10.394742 -49.514218 -0.894531 +VERTEX_SE2 1197 10.994633 -50.274829 -0.827087 +VERTEX_SE2 1198 11.658168 -51.007205 -0.854883 +VERTEX_SE2 1199 12.254866 -51.767024 -0.841914 +VERTEX_SE2 1200 11.531563 -52.449033 -2.412914 +VERTEX_SE2 1201 10.816710 -53.128763 -2.418906 +VERTEX_SE2 1202 10.026793 -53.770592 -2.414216 +VERTEX_SE2 1203 9.268184 -54.439535 -2.388730 +VERTEX_SE2 1204 8.561862 -53.680046 2.304490 +VERTEX_SE2 1205 7.904546 -52.948681 2.323350 +VERTEX_SE2 1206 7.215007 -52.247313 2.326900 +VERTEX_SE2 1207 6.533035 -51.531014 2.287417 +VERTEX_SE2 1208 7.184899 -52.287688 -0.847713 +VERTEX_SE2 1209 7.875418 -53.046953 -0.887681 +VERTEX_SE2 1210 8.476526 -53.821988 -0.846616 +VERTEX_SE2 1211 9.131934 -54.618589 -0.876579 +VERTEX_SE2 1212 8.465414 -53.873588 2.267461 +VERTEX_SE2 1213 7.816981 -53.119656 2.237904 +VERTEX_SE2 1214 7.173946 -52.299504 2.220569 +VERTEX_SE2 1215 6.571637 -51.528192 2.238290 +VERTEX_SE2 1216 7.386051 -50.915725 0.673980 +VERTEX_SE2 1217 8.195676 -50.301634 0.704810 +VERTEX_SE2 1218 8.986606 -49.660565 0.744984 +VERTEX_SE2 1219 9.729104 -48.976851 0.722059 +VERTEX_SE2 1220 10.442622 -48.292841 0.728474 +VERTEX_SE2 1221 11.177428 -47.641792 0.739265 +VERTEX_SE2 1222 11.925402 -46.959613 0.731019 +VERTEX_SE2 1223 12.681167 -46.332176 0.727296 +VERTEX_SE2 1224 12.016859 -45.556000 2.309636 +VERTEX_SE2 1225 11.364435 -44.817526 2.311628 +VERTEX_SE2 1226 10.710443 -44.049558 2.300973 +VERTEX_SE2 1227 10.056449 -43.320618 2.272522 +VERTEX_SE2 1228 10.792008 -42.691885 0.708452 +VERTEX_SE2 1229 11.543065 -42.000156 0.713145 +VERTEX_SE2 1230 12.294621 -41.355003 0.703163 +VERTEX_SE2 1231 13.089141 -40.668711 0.695326 +VERTEX_SE2 1232 12.460380 -39.904758 2.229336 +VERTEX_SE2 1233 11.826477 -39.144628 2.265380 +VERTEX_SE2 1234 11.203805 -38.378122 2.287527 +VERTEX_SE2 1235 10.532223 -37.626804 2.260987 +VERTEX_SE2 1236 9.920020 -36.869935 2.225273 +VERTEX_SE2 1237 9.321568 -36.094176 2.229863 +VERTEX_SE2 1238 8.751016 -35.309394 2.217183 +VERTEX_SE2 1239 8.113261 -34.579194 2.222681 +VERTEX_SE2 1240 8.731829 -35.370627 -0.907569 +VERTEX_SE2 1241 9.343091 -36.132431 -0.850708 +VERTEX_SE2 1242 10.022292 -36.895081 -0.851833 +VERTEX_SE2 1243 10.700701 -37.672337 -0.838011 +VERTEX_SE2 1244 9.949919 -38.311259 -2.397621 +VERTEX_SE2 1245 9.219150 -38.971263 -2.391321 +VERTEX_SE2 1246 8.499906 -39.637114 -2.412053 +VERTEX_SE2 1247 7.786980 -40.326552 -2.423176 +VERTEX_SE2 1248 7.108131 -39.537581 2.234884 +VERTEX_SE2 1249 6.507471 -38.745364 2.250727 +VERTEX_SE2 1250 5.849622 -37.939254 2.231089 +VERTEX_SE2 1251 5.239986 -37.166138 2.254131 +VERTEX_SE2 1252 5.893370 -37.956734 -0.882519 +VERTEX_SE2 1253 6.536012 -38.728995 -0.900344 +VERTEX_SE2 1254 7.159271 -39.479475 -0.891211 +VERTEX_SE2 1255 7.775713 -40.245664 -0.855569 +VERTEX_SE2 1256 6.984288 -40.871687 -2.420639 +VERTEX_SE2 1257 6.258694 -41.584715 -2.458957 +VERTEX_SE2 1258 5.453651 -42.225474 -2.494737 +VERTEX_SE2 1259 4.681332 -42.845358 -2.472164 +VERTEX_SE2 1260 5.301558 -43.595755 -0.859404 +VERTEX_SE2 1261 5.931133 -44.363359 -0.904376 +VERTEX_SE2 1262 6.545869 -45.178438 -0.909736 +VERTEX_SE2 1263 7.149913 -45.965737 -0.878413 +VERTEX_SE2 1264 6.526916 -45.170461 2.224897 +VERTEX_SE2 1265 5.926008 -44.365517 2.226082 +VERTEX_SE2 1266 5.298830 -43.573642 2.233519 +VERTEX_SE2 1267 4.669084 -42.791753 2.255223 +VERTEX_SE2 1268 5.315448 -43.548760 -0.910667 +VERTEX_SE2 1269 5.939444 -44.356448 -0.961417 +VERTEX_SE2 1270 6.511578 -45.169542 -0.964686 +VERTEX_SE2 1271 7.061695 -45.959203 -0.966971 +VERTEX_SE2 1272 6.228094 -46.536127 -2.565691 +VERTEX_SE2 1273 5.346203 -47.091473 -2.571093 +VERTEX_SE2 1274 4.484377 -47.604665 -2.556762 +VERTEX_SE2 1275 3.670092 -48.173041 -2.558331 +VERTEX_SE2 1276 4.219384 -48.983793 -1.011031 +VERTEX_SE2 1277 4.723763 -49.870799 -1.012247 +VERTEX_SE2 1278 5.260258 -50.700104 -1.009588 +VERTEX_SE2 1279 5.789884 -51.561711 -0.985418 +VERTEX_SE2 1280 6.605689 -50.973050 0.606222 +VERTEX_SE2 1281 7.432897 -50.412474 0.622595 +VERTEX_SE2 1282 8.301759 -49.841563 0.634508 +VERTEX_SE2 1283 9.119657 -49.253817 0.618640 +VERTEX_SE2 1284 8.575343 -48.409833 2.156130 +VERTEX_SE2 1285 8.029107 -47.551797 2.148422 +VERTEX_SE2 1286 7.454510 -46.714698 2.142653 +VERTEX_SE2 1287 6.868104 -45.883467 2.135977 +VERTEX_SE2 1288 6.048114 -46.419483 -2.590783 +VERTEX_SE2 1289 5.191950 -46.945589 -2.575635 +VERTEX_SE2 1290 4.347434 -47.456532 -2.573046 +VERTEX_SE2 1291 3.526107 -48.035166 -2.539378 +VERTEX_SE2 1292 4.338355 -47.462094 0.599622 +VERTEX_SE2 1293 5.187379 -46.902920 0.597881 +VERTEX_SE2 1294 6.000601 -46.337747 0.575779 +VERTEX_SE2 1295 6.835953 -45.802950 0.577543 +VERTEX_SE2 1296 7.373465 -46.644996 -0.985897 +VERTEX_SE2 1297 7.928884 -47.482813 -0.966766 +VERTEX_SE2 1298 8.498905 -48.332173 -0.964993 +VERTEX_SE2 1299 9.082799 -49.149607 -0.949605 +VERTEX_SE2 1300 8.289943 -49.732772 -2.530385 +VERTEX_SE2 1301 7.532998 -50.303772 -2.573017 +VERTEX_SE2 1302 6.683251 -50.840895 -2.589515 +VERTEX_SE2 1303 5.830725 -51.367932 -2.613827 +VERTEX_SE2 1304 6.702307 -50.843729 0.550743 +VERTEX_SE2 1305 7.542500 -50.323822 0.567453 +VERTEX_SE2 1306 8.350578 -49.759627 0.611809 +VERTEX_SE2 1307 9.150398 -49.175239 0.593948 +VERTEX_SE2 1308 9.680564 -49.983750 -1.012052 +VERTEX_SE2 1309 10.268131 -50.792123 -1.000705 +VERTEX_SE2 1310 10.825489 -51.607954 -0.954701 +VERTEX_SE2 1311 11.471893 -52.411607 -0.970649 +VERTEX_SE2 1312 10.658785 -53.010602 -2.595559 +VERTEX_SE2 1313 9.809891 -53.496969 -2.615840 +VERTEX_SE2 1314 8.949506 -53.975277 -2.590191 +VERTEX_SE2 1315 8.098054 -54.480336 -2.522070 +VERTEX_SE2 1316 8.920725 -53.946413 0.618410 +VERTEX_SE2 1317 9.724505 -53.361872 0.605895 +VERTEX_SE2 1318 10.554612 -52.758115 0.581750 +VERTEX_SE2 1319 11.355225 -52.189051 0.622719 +VERTEX_SE2 1320 10.709361 -51.374812 2.196569 +VERTEX_SE2 1321 10.135224 -50.563977 2.190859 +VERTEX_SE2 1322 9.522614 -49.722142 2.172991 +VERTEX_SE2 1323 8.918054 -48.873483 2.205562 +VERTEX_SE2 1324 9.513575 -49.688627 -0.897628 +VERTEX_SE2 1325 10.104939 -50.433712 -0.922679 +VERTEX_SE2 1326 10.714703 -51.253665 -0.903256 +VERTEX_SE2 1327 11.348723 -52.051842 -0.919302 +VERTEX_SE2 1328 10.597672 -52.663160 -2.495762 +VERTEX_SE2 1329 9.784171 -53.234053 -2.496430 +VERTEX_SE2 1330 8.979634 -53.831320 -2.505905 +VERTEX_SE2 1331 8.133552 -54.436793 -2.503042 +VERTEX_SE2 1332 8.723423 -55.238900 -0.945422 +VERTEX_SE2 1333 9.299906 -56.046046 -0.933389 +VERTEX_SE2 1334 9.908157 -56.844290 -0.920805 +VERTEX_SE2 1335 10.470651 -57.656631 -0.931042 +VERTEX_SE2 1336 11.292315 -57.046518 0.666108 +VERTEX_SE2 1337 12.119383 -56.431560 0.670809 +VERTEX_SE2 1338 12.914576 -55.844443 0.640213 +VERTEX_SE2 1339 13.702867 -55.192490 0.663368 +VERTEX_SE2 1340 12.915190 -55.836623 -2.478962 +VERTEX_SE2 1341 12.121525 -56.455166 -2.476707 +VERTEX_SE2 1342 11.321962 -57.110295 -2.513003 +VERTEX_SE2 1343 10.524157 -57.671810 -2.496786 +VERTEX_SE2 1344 11.142568 -58.459717 -0.913286 +VERTEX_SE2 1345 11.763485 -59.238376 -0.898994 +VERTEX_SE2 1346 12.367586 -60.018947 -0.893119 +VERTEX_SE2 1347 12.983790 -60.818966 -0.919359 +VERTEX_SE2 1348 13.751208 -60.179238 0.648171 +VERTEX_SE2 1349 14.569544 -59.576235 0.640971 +VERTEX_SE2 1350 15.415638 -58.956906 0.624435 +VERTEX_SE2 1351 16.214258 -58.362577 0.660863 +VERTEX_SE2 1352 16.830684 -59.154506 -0.906857 +VERTEX_SE2 1353 17.433674 -59.930941 -0.913723 +VERTEX_SE2 1354 18.041027 -60.713273 -0.906773 +VERTEX_SE2 1355 18.645819 -61.513840 -0.856047 +VERTEX_SE2 1356 19.365541 -60.895644 0.696463 +VERTEX_SE2 1357 20.134917 -60.244290 0.679116 +VERTEX_SE2 1358 20.874664 -59.619477 0.611878 +VERTEX_SE2 1359 21.684960 -59.049672 0.621794 +VERTEX_SE2 1360 21.074651 -58.221166 2.187794 +VERTEX_SE2 1361 20.469760 -57.397379 2.215643 +VERTEX_SE2 1362 19.912808 -56.610911 2.227058 +VERTEX_SE2 1363 19.308077 -55.813732 2.246692 +VERTEX_SE2 1364 20.102356 -55.188047 0.688712 +VERTEX_SE2 1365 20.842876 -54.595022 0.655947 +VERTEX_SE2 1366 21.621733 -53.983495 0.655392 +VERTEX_SE2 1367 22.438138 -53.364306 0.650466 +VERTEX_SE2 1368 23.033417 -54.190623 -0.884014 +VERTEX_SE2 1369 23.687757 -54.940523 -0.901664 +VERTEX_SE2 1370 24.318692 -55.735448 -0.901170 +VERTEX_SE2 1371 24.922779 -56.485457 -0.913631 +VERTEX_SE2 1372 24.153427 -57.155157 -2.499991 +VERTEX_SE2 1373 23.368205 -57.768866 -2.521488 +VERTEX_SE2 1374 22.557264 -58.339589 -2.540365 +VERTEX_SE2 1375 21.722666 -58.922957 -2.548257 +VERTEX_SE2 1376 21.110337 -58.081954 2.152573 +VERTEX_SE2 1377 20.562439 -57.209104 2.133134 +VERTEX_SE2 1378 20.082286 -56.381977 2.145636 +VERTEX_SE2 1379 19.502137 -55.547293 2.194813 +VERTEX_SE2 1380 20.079882 -56.342695 -0.958517 +VERTEX_SE2 1381 20.611643 -57.148204 -0.990002 +VERTEX_SE2 1382 21.142863 -57.977996 -1.006842 +VERTEX_SE2 1383 21.671571 -58.864679 -0.995386 +VERTEX_SE2 1384 20.803042 -59.381919 -2.573176 +VERTEX_SE2 1385 19.938871 -59.890997 -2.562210 +VERTEX_SE2 1386 19.139239 -60.444100 -2.519845 +VERTEX_SE2 1387 18.325345 -61.032686 -2.522918 +VERTEX_SE2 1388 18.908696 -61.846599 -0.947478 +VERTEX_SE2 1389 19.492856 -62.645325 -0.953920 +VERTEX_SE2 1390 20.090837 -63.459709 -0.985926 +VERTEX_SE2 1391 20.611373 -64.263053 -0.985015 +VERTEX_SE2 1392 20.035054 -63.433366 2.195615 +VERTEX_SE2 1393 19.442495 -62.591154 2.208110 +VERTEX_SE2 1394 18.869768 -61.823352 2.209979 +VERTEX_SE2 1395 18.273998 -61.052797 2.199529 +VERTEX_SE2 1396 18.873216 -61.797899 -0.937911 +VERTEX_SE2 1397 19.450865 -62.623406 -0.899058 +VERTEX_SE2 1398 20.064691 -63.387949 -0.931717 +VERTEX_SE2 1399 20.683491 -64.201363 -0.935232 +VERTEX_SE2 1400 20.101306 -63.383373 2.198048 +VERTEX_SE2 1401 19.542360 -62.617394 2.233834 +VERTEX_SE2 1402 18.932342 -61.856765 2.229820 +VERTEX_SE2 1403 18.329083 -61.058125 2.261942 +VERTEX_SE2 1404 18.898926 -61.824348 -0.888988 +VERTEX_SE2 1405 19.531163 -62.584698 -0.853777 +VERTEX_SE2 1406 20.189469 -63.312709 -0.838833 +VERTEX_SE2 1407 20.884572 -64.056408 -0.843511 +VERTEX_SE2 1408 21.607529 -63.406896 0.736779 +VERTEX_SE2 1409 22.352269 -62.716221 0.710234 +VERTEX_SE2 1410 23.153573 -62.070612 0.695932 +VERTEX_SE2 1411 23.988235 -61.426685 0.673751 +VERTEX_SE2 1412 23.234103 -62.074301 -2.488149 +VERTEX_SE2 1413 22.404883 -62.683395 -2.484997 +VERTEX_SE2 1414 21.625692 -63.313584 -2.483364 +VERTEX_SE2 1415 20.845150 -63.904120 -2.499940 +VERTEX_SE2 1416 20.267371 -63.107651 2.183300 +VERTEX_SE2 1417 19.720437 -62.291127 2.166974 +VERTEX_SE2 1418 19.178082 -61.438176 2.159743 +VERTEX_SE2 1419 18.654206 -60.606426 2.165732 +VERTEX_SE2 1420 19.203496 -61.423384 -0.935578 +VERTEX_SE2 1421 19.800899 -62.218453 -0.918306 +VERTEX_SE2 1422 20.398626 -62.991987 -0.897398 +VERTEX_SE2 1423 21.025334 -63.775345 -0.917212 +VERTEX_SE2 1424 21.817507 -63.163775 0.614598 +VERTEX_SE2 1425 22.621319 -62.566648 0.634221 +VERTEX_SE2 1426 23.413410 -61.986903 0.614619 +VERTEX_SE2 1427 24.203607 -61.402575 0.607379 +VERTEX_SE2 1428 24.779998 -62.217081 -0.965311 +VERTEX_SE2 1429 25.328079 -63.003678 -0.947907 +VERTEX_SE2 1430 25.889178 -63.814487 -0.927790 +VERTEX_SE2 1431 26.503707 -64.641913 -0.941588 +VERTEX_SE2 1432 25.676057 -65.250422 -2.543018 +VERTEX_SE2 1433 24.879775 -65.824819 -2.559708 +VERTEX_SE2 1434 24.035083 -66.397401 -2.561931 +VERTEX_SE2 1435 23.172049 -66.932169 -2.586304 +VERTEX_SE2 1436 22.670381 -66.132156 2.116286 +VERTEX_SE2 1437 22.142054 -65.261565 2.150043 +VERTEX_SE2 1438 21.624116 -64.432270 2.124994 +VERTEX_SE2 1439 21.121670 -63.608508 2.102745 +VERTEX_SE2 1440 20.263214 -64.145687 -2.600905 +VERTEX_SE2 1441 19.393693 -64.673352 -2.596765 +VERTEX_SE2 1442 18.534190 -65.177783 -2.579328 +VERTEX_SE2 1443 17.723495 -65.694155 -2.618840 +VERTEX_SE2 1444 18.191151 -66.600458 -1.036330 +VERTEX_SE2 1445 18.697698 -67.439234 -1.043298 +VERTEX_SE2 1446 19.195538 -68.318667 -1.030743 +VERTEX_SE2 1447 19.705991 -69.171632 -0.999000 +VERTEX_SE2 1448 19.191899 -68.356480 2.137440 +VERTEX_SE2 1449 18.665365 -67.503703 2.113758 +VERTEX_SE2 1450 18.113705 -66.645414 2.137110 +VERTEX_SE2 1451 17.574082 -65.774597 2.144411 +VERTEX_SE2 1452 17.013567 -64.937430 2.118094 +VERTEX_SE2 1453 16.482591 -64.069518 2.084030 +VERTEX_SE2 1454 16.003962 -63.213084 2.078350 +VERTEX_SE2 1455 15.506392 -62.337687 2.103789 +VERTEX_SE2 1456 16.417929 -61.848638 0.524659 +VERTEX_SE2 1457 17.289234 -61.352987 0.518244 +VERTEX_SE2 1458 18.120847 -60.864732 0.501848 +VERTEX_SE2 1459 18.988770 -60.401673 0.515385 +VERTEX_SE2 1460 18.491549 -59.551567 2.139995 +VERTEX_SE2 1461 17.942622 -58.672804 2.086123 +VERTEX_SE2 1462 17.449797 -57.775588 2.085247 +VERTEX_SE2 1463 16.962780 -56.876859 2.057308 +VERTEX_SE2 1464 17.859567 -56.417827 0.478668 +VERTEX_SE2 1465 18.726827 -55.938392 0.477685 +VERTEX_SE2 1466 19.580361 -55.481938 0.479995 +VERTEX_SE2 1467 20.448937 -55.004268 0.494923 +VERTEX_SE2 1468 19.976539 -54.200063 2.055323 +VERTEX_SE2 1469 19.552190 -53.294488 2.042890 +VERTEX_SE2 1470 19.061897 -52.417840 2.039799 +VERTEX_SE2 1471 18.630355 -51.532571 2.004245 +VERTEX_SE2 1472 19.499998 -51.119788 0.415205 +VERTEX_SE2 1473 20.421671 -50.712234 0.449718 +VERTEX_SE2 1474 21.314070 -50.312576 0.466884 +VERTEX_SE2 1475 22.200397 -49.847771 0.476425 +VERTEX_SE2 1476 21.338946 -50.295003 -2.660055 +VERTEX_SE2 1477 20.456970 -50.777227 -2.699570 +VERTEX_SE2 1478 19.540862 -51.218777 -2.681882 +VERTEX_SE2 1479 18.650622 -51.672550 -2.699294 +VERTEX_SE2 1480 19.097044 -52.584091 -1.089204 +VERTEX_SE2 1481 19.564460 -53.459385 -1.114564 +VERTEX_SE2 1482 19.974326 -54.352679 -1.164358 +VERTEX_SE2 1483 20.365388 -55.282157 -1.146836 +VERTEX_SE2 1484 21.271489 -54.877956 0.429394 +VERTEX_SE2 1485 22.179694 -54.501589 0.448987 +VERTEX_SE2 1486 23.076330 -54.075400 0.441007 +VERTEX_SE2 1487 24.028031 -53.665454 0.449236 +VERTEX_SE2 1488 24.464678 -54.591046 -1.084284 +VERTEX_SE2 1489 24.942493 -55.496349 -1.089449 +VERTEX_SE2 1490 25.398848 -56.363320 -1.076559 +VERTEX_SE2 1491 25.858480 -57.222320 -1.101631 +VERTEX_SE2 1492 26.737882 -56.726722 0.435719 +VERTEX_SE2 1493 27.673754 -56.297380 0.435286 +VERTEX_SE2 1494 28.593150 -55.905293 0.428478 +VERTEX_SE2 1495 29.498214 -55.470082 0.406172 +VERTEX_SE2 1496 29.921433 -56.366328 -1.169828 +VERTEX_SE2 1497 30.285352 -57.277126 -1.172690 +VERTEX_SE2 1498 30.689502 -58.176950 -1.175818 +VERTEX_SE2 1499 31.082598 -59.122948 -1.184807 +VERTEX_SE2 1500 31.948736 -58.729220 0.384183 +VERTEX_SE2 1501 32.887056 -58.336509 0.343163 +VERTEX_SE2 1502 33.792425 -57.990647 0.343099 +VERTEX_SE2 1503 34.727369 -57.691324 0.379276 +VERTEX_SE2 1504 33.810988 -58.065839 -2.776844 +VERTEX_SE2 1505 32.888101 -58.429244 -2.745890 +VERTEX_SE2 1506 31.937833 -58.847925 -2.795193 +VERTEX_SE2 1507 30.944646 -59.173826 -2.765360 +VERTEX_SE2 1508 31.855310 -58.816248 0.389450 +VERTEX_SE2 1509 32.764412 -58.440241 0.435773 +VERTEX_SE2 1510 33.689912 -58.017477 0.433908 +VERTEX_SE2 1511 34.627500 -57.592405 0.433492 +VERTEX_SE2 1512 33.701218 -57.981831 -2.688978 +VERTEX_SE2 1513 32.803821 -58.430829 -2.691655 +VERTEX_SE2 1514 31.890661 -58.851981 -2.668258 +VERTEX_SE2 1515 30.989672 -59.295611 -2.664260 +VERTEX_SE2 1516 31.409058 -60.152718 -1.080730 +VERTEX_SE2 1517 31.878673 -61.044532 -1.093121 +VERTEX_SE2 1518 32.296832 -61.912443 -1.089794 +VERTEX_SE2 1519 32.759703 -62.788061 -1.085070 +VERTEX_SE2 1520 32.274746 -61.903412 2.067420 +VERTEX_SE2 1521 31.799404 -60.994799 2.084099 +VERTEX_SE2 1522 31.249932 -60.070700 2.049189 +VERTEX_SE2 1523 30.822881 -59.192554 2.017884 +VERTEX_SE2 1524 31.728743 -58.756638 0.507484 +VERTEX_SE2 1525 32.578969 -58.260004 0.509749 +VERTEX_SE2 1526 33.451132 -57.756769 0.511011 +VERTEX_SE2 1527 34.321007 -57.274916 0.507474 +VERTEX_SE2 1528 33.422543 -57.791480 -2.610236 +VERTEX_SE2 1529 32.546491 -58.304970 -2.644333 +VERTEX_SE2 1530 31.650082 -58.774978 -2.648829 +VERTEX_SE2 1531 30.773190 -59.278617 -2.648468 +VERTEX_SE2 1532 31.650671 -58.852389 0.525042 +VERTEX_SE2 1533 32.528161 -58.310512 0.535847 +VERTEX_SE2 1534 33.409136 -57.812900 0.573876 +VERTEX_SE2 1535 34.252747 -57.280074 0.571291 +VERTEX_SE2 1536 34.740098 -58.142689 -1.040669 +VERTEX_SE2 1537 35.256164 -59.004458 -1.080697 +VERTEX_SE2 1538 35.768122 -59.872765 -1.113698 +VERTEX_SE2 1539 36.204337 -60.786633 -1.123071 +VERTEX_SE2 1540 35.764377 -59.904905 2.012759 +VERTEX_SE2 1541 35.337452 -58.985572 2.016549 +VERTEX_SE2 1542 34.913415 -58.084738 1.974851 +VERTEX_SE2 1543 34.505790 -57.172332 1.949013 +VERTEX_SE2 1544 34.894989 -58.112340 -1.210867 +VERTEX_SE2 1545 35.262947 -59.023616 -1.239841 +VERTEX_SE2 1546 35.584239 -59.970003 -1.255029 +VERTEX_SE2 1547 35.937431 -60.905328 -1.278092 +VERTEX_SE2 1548 35.654682 -59.944642 1.895418 +VERTEX_SE2 1549 35.314836 -59.012339 1.901911 +VERTEX_SE2 1550 35.005439 -58.052971 1.891153 +VERTEX_SE2 1551 34.715691 -57.118924 1.935982 +VERTEX_SE2 1552 33.774446 -57.486538 -2.782188 +VERTEX_SE2 1553 32.860091 -57.826802 -2.812224 +VERTEX_SE2 1554 31.858921 -58.159304 -2.797868 +VERTEX_SE2 1555 30.914765 -58.493703 -2.842679 +VERTEX_SE2 1556 30.568884 -57.531335 1.885571 +VERTEX_SE2 1557 30.272178 -56.586224 1.858765 +VERTEX_SE2 1558 30.017119 -55.666674 1.890703 +VERTEX_SE2 1559 29.726559 -54.729727 1.890267 +VERTEX_SE2 1560 30.037434 -55.659901 -1.247953 +VERTEX_SE2 1561 30.306698 -56.590802 -1.244920 +VERTEX_SE2 1562 30.657218 -57.560005 -1.263682 +VERTEX_SE2 1563 30.985555 -58.501415 -1.260742 +VERTEX_SE2 1564 30.060441 -58.785342 -2.817642 +VERTEX_SE2 1565 29.109590 -59.082768 -2.836949 +VERTEX_SE2 1566 28.142424 -59.374141 -2.825307 +VERTEX_SE2 1567 27.182592 -59.681847 -2.832040 +VERTEX_SE2 1568 27.497314 -60.695712 -1.241570 +VERTEX_SE2 1569 27.831796 -61.650076 -1.251329 +VERTEX_SE2 1570 28.095714 -62.623303 -1.224158 +VERTEX_SE2 1571 28.467192 -63.592134 -1.234437 +VERTEX_SE2 1572 28.154358 -62.715915 1.924493 +VERTEX_SE2 1573 27.836600 -61.781552 1.935717 +VERTEX_SE2 1574 27.479313 -60.862141 1.947571 +VERTEX_SE2 1575 27.111932 -59.932852 1.965953 +VERTEX_SE2 1576 28.028954 -59.586288 0.379713 +VERTEX_SE2 1577 28.951872 -59.236802 0.377301 +VERTEX_SE2 1578 29.898485 -58.862686 0.361118 +VERTEX_SE2 1579 30.811608 -58.506958 0.349565 +VERTEX_SE2 1580 30.510783 -57.557479 1.930135 +VERTEX_SE2 1581 30.150550 -56.664312 1.900506 +VERTEX_SE2 1582 29.788716 -55.720537 1.904090 +VERTEX_SE2 1583 29.409542 -54.784623 1.905053 +VERTEX_SE2 1584 28.484735 -55.098850 -2.822337 +VERTEX_SE2 1585 27.548554 -55.382756 -2.804671 +VERTEX_SE2 1586 26.640737 -55.720744 -2.841263 +VERTEX_SE2 1587 25.663055 -56.000798 -2.847504 +VERTEX_SE2 1588 25.401070 -55.119376 1.877886 +VERTEX_SE2 1589 25.096589 -54.143838 1.872046 +VERTEX_SE2 1590 24.790081 -53.177872 1.840482 +VERTEX_SE2 1591 24.513430 -52.220211 1.846791 +VERTEX_SE2 1592 23.529065 -52.474186 -2.901229 +VERTEX_SE2 1593 22.571487 -52.701882 -2.882277 +VERTEX_SE2 1594 21.591348 -52.946993 -2.875577 +VERTEX_SE2 1595 20.641627 -53.229163 -2.869927 +VERTEX_SE2 1596 20.945972 -54.163998 -1.282787 +VERTEX_SE2 1597 21.259303 -55.152890 -1.287257 +VERTEX_SE2 1598 21.523100 -56.124194 -1.287705 +VERTEX_SE2 1599 21.808759 -57.141182 -1.270503 +VERTEX_SE2 1600 22.764905 -56.813725 0.299447 +VERTEX_SE2 1601 23.740453 -56.525603 0.288462 +VERTEX_SE2 1602 24.705848 -56.224304 0.325338 +VERTEX_SE2 1603 25.648292 -55.892537 0.319688 +VERTEX_SE2 1604 25.336817 -54.946655 1.879638 +VERTEX_SE2 1605 24.985385 -53.949684 1.881897 +VERTEX_SE2 1606 24.688503 -53.021827 1.891783 +VERTEX_SE2 1607 24.320331 -52.090214 1.912209 +VERTEX_SE2 1608 23.368126 -52.423182 -2.807171 +VERTEX_SE2 1609 22.407865 -52.733298 -2.824084 +VERTEX_SE2 1610 21.450055 -53.003111 -2.825408 +VERTEX_SE2 1611 20.519594 -53.314363 -2.804421 +VERTEX_SE2 1612 21.474766 -52.978653 0.353109 +VERTEX_SE2 1613 22.459867 -52.628618 0.370812 +VERTEX_SE2 1614 23.387149 -52.251982 0.430112 +VERTEX_SE2 1615 24.270349 -51.837816 0.408788 +VERTEX_SE2 1616 24.692125 -52.807009 -1.192282 +VERTEX_SE2 1617 25.090041 -53.735539 -1.186112 +VERTEX_SE2 1618 25.498057 -54.631938 -1.180619 +VERTEX_SE2 1619 25.861882 -55.597366 -1.180506 +VERTEX_SE2 1620 25.488415 -54.666589 1.937124 +VERTEX_SE2 1621 25.152060 -53.722282 1.926538 +VERTEX_SE2 1622 24.803668 -52.801301 1.918108 +VERTEX_SE2 1623 24.466763 -51.878256 1.894547 +VERTEX_SE2 1624 25.430315 -51.553208 0.319027 +VERTEX_SE2 1625 26.351451 -51.256602 0.335721 +VERTEX_SE2 1626 27.300439 -50.905500 0.353895 +VERTEX_SE2 1627 28.251151 -50.562714 0.354032 +VERTEX_SE2 1628 28.603691 -51.510600 -1.207998 +VERTEX_SE2 1629 28.978852 -52.457409 -1.222451 +VERTEX_SE2 1630 29.299344 -53.399885 -1.234101 +VERTEX_SE2 1631 29.651927 -54.401830 -1.198809 +VERTEX_SE2 1632 28.720196 -54.764726 -2.756719 +VERTEX_SE2 1633 27.775512 -55.136298 -2.761518 +VERTEX_SE2 1634 26.828257 -55.506830 -2.760786 +VERTEX_SE2 1635 25.950410 -55.888326 -2.747507 +VERTEX_SE2 1636 26.844825 -55.481397 0.368703 +VERTEX_SE2 1637 27.758936 -55.142038 0.401403 +VERTEX_SE2 1638 28.637315 -54.787502 0.411478 +VERTEX_SE2 1639 29.564147 -54.421372 0.408239 +VERTEX_SE2 1640 29.176054 -53.514393 1.941859 +VERTEX_SE2 1641 28.844869 -52.569420 1.981728 +VERTEX_SE2 1642 28.427677 -51.666200 1.989528 +VERTEX_SE2 1643 28.019888 -50.721414 1.952181 +VERTEX_SE2 1644 27.039303 -51.098946 -2.786209 +VERTEX_SE2 1645 26.099859 -51.473338 -2.783777 +VERTEX_SE2 1646 25.181497 -51.787696 -2.761353 +VERTEX_SE2 1647 24.281448 -52.174030 -2.757666 +VERTEX_SE2 1648 24.670224 -53.115961 -1.188876 +VERTEX_SE2 1649 25.026769 -54.032101 -1.192437 +VERTEX_SE2 1650 25.364872 -54.911764 -1.186176 +VERTEX_SE2 1651 25.768813 -55.821357 -1.173224 +VERTEX_SE2 1652 24.869004 -56.218633 -2.717054 +VERTEX_SE2 1653 23.979391 -56.609137 -2.732264 +VERTEX_SE2 1654 23.064393 -57.020404 -2.720287 +VERTEX_SE2 1655 22.163733 -57.434027 -2.730331 +VERTEX_SE2 1656 22.547043 -58.353328 -1.156871 +VERTEX_SE2 1657 22.936372 -59.276085 -1.164748 +VERTEX_SE2 1658 23.324376 -60.208006 -1.160210 +VERTEX_SE2 1659 23.688380 -61.120239 -1.162062 +VERTEX_SE2 1660 24.083628 -62.047437 -1.163571 +VERTEX_SE2 1661 24.506234 -62.951550 -1.166953 +VERTEX_SE2 1662 24.873930 -63.839970 -1.185513 +VERTEX_SE2 1663 25.276798 -64.766981 -1.132796 +VERTEX_SE2 1664 24.390066 -65.198230 -2.732966 +VERTEX_SE2 1665 23.448930 -65.597200 -2.725971 +VERTEX_SE2 1666 22.514469 -65.982192 -2.687352 +VERTEX_SE2 1667 21.618972 -66.418133 -2.699676 +VERTEX_SE2 1668 22.555580 -66.006537 0.459404 +VERTEX_SE2 1669 23.465723 -65.582974 0.465519 +VERTEX_SE2 1670 24.357723 -65.146632 0.439391 +VERTEX_SE2 1671 25.243604 -64.693333 0.450269 +VERTEX_SE2 1672 24.769467 -63.802003 1.993979 +VERTEX_SE2 1673 24.360506 -62.915489 2.018633 +VERTEX_SE2 1674 23.945417 -62.009954 2.077958 +VERTEX_SE2 1675 23.449177 -61.141746 2.078322 +VERTEX_SE2 1676 24.302878 -60.619973 0.524672 +VERTEX_SE2 1677 25.115163 -60.150404 0.510464 +VERTEX_SE2 1678 26.032458 -59.635949 0.503828 +VERTEX_SE2 1679 26.897773 -59.191698 0.514629 +VERTEX_SE2 1680 26.387852 -58.355212 2.141339 +VERTEX_SE2 1681 25.841178 -57.526279 2.193387 +VERTEX_SE2 1682 25.256369 -56.694807 2.206869 +VERTEX_SE2 1683 24.661027 -55.905160 2.204661 +VERTEX_SE2 1684 23.853310 -56.522566 -2.529699 +VERTEX_SE2 1685 23.051047 -57.090585 -2.535489 +VERTEX_SE2 1686 22.231334 -57.673764 -2.530676 +VERTEX_SE2 1687 21.409097 -58.198747 -2.541884 +VERTEX_SE2 1688 20.837777 -57.357820 2.200276 +VERTEX_SE2 1689 20.221084 -56.589988 2.255095 +VERTEX_SE2 1690 19.568513 -55.829516 2.240124 +VERTEX_SE2 1691 18.951278 -55.037779 2.191155 +VERTEX_SE2 1692 18.139723 -55.613615 -2.527335 +VERTEX_SE2 1693 17.325732 -56.163888 -2.557440 +VERTEX_SE2 1694 16.515226 -56.730408 -2.584915 +VERTEX_SE2 1695 15.679327 -57.266124 -2.567386 +VERTEX_SE2 1696 15.172059 -56.390960 2.136224 +VERTEX_SE2 1697 14.631930 -55.529631 2.139799 +VERTEX_SE2 1698 14.117238 -54.705056 2.172278 +VERTEX_SE2 1699 13.559512 -53.890476 2.182823 +VERTEX_SE2 1700 12.965967 -53.061540 2.194414 +VERTEX_SE2 1701 12.422162 -52.226473 2.210739 +VERTEX_SE2 1702 11.795484 -51.420045 2.215615 +VERTEX_SE2 1703 11.213682 -50.639732 2.215440 +VERTEX_SE2 1704 10.393028 -51.275796 -2.514800 +VERTEX_SE2 1705 9.537573 -51.826466 -2.500809 +VERTEX_SE2 1706 8.744327 -52.423291 -2.528343 +VERTEX_SE2 1707 7.929415 -52.990827 -2.521690 +VERTEX_SE2 1708 8.763819 -52.406446 0.581970 +VERTEX_SE2 1709 9.597457 -51.893769 0.557047 +VERTEX_SE2 1710 10.425645 -51.327291 0.583890 +VERTEX_SE2 1711 11.256951 -50.760727 0.620479 +VERTEX_SE2 1712 12.047322 -50.189701 0.600516 +VERTEX_SE2 1713 12.894230 -49.637195 0.571508 +VERTEX_SE2 1714 13.706720 -49.084867 0.562315 +VERTEX_SE2 1715 14.542643 -48.535709 0.578572 +VERTEX_SE2 1716 15.040507 -49.342131 -0.982248 +VERTEX_SE2 1717 15.597077 -50.199468 -0.994377 +VERTEX_SE2 1718 16.108316 -51.062988 -0.993861 +VERTEX_SE2 1719 16.641533 -51.903250 -0.991373 +VERTEX_SE2 1720 16.098170 -51.079770 2.143337 +VERTEX_SE2 1721 15.562623 -50.235585 2.163429 +VERTEX_SE2 1722 14.979477 -49.407318 2.164949 +VERTEX_SE2 1723 14.412980 -48.575129 2.151011 +VERTEX_SE2 1724 15.248580 -48.055892 0.591431 +VERTEX_SE2 1725 16.108481 -47.497306 0.540070 +VERTEX_SE2 1726 16.984479 -46.937617 0.523363 +VERTEX_SE2 1727 17.870761 -46.407174 0.513243 +VERTEX_SE2 1728 18.327596 -47.302457 -1.027257 +VERTEX_SE2 1729 18.826563 -48.143017 -1.025248 +VERTEX_SE2 1730 19.326652 -48.992729 -1.056474 +VERTEX_SE2 1731 19.792382 -49.891687 -1.086075 +VERTEX_SE2 1732 19.340849 -49.027010 2.055085 +VERTEX_SE2 1733 18.833094 -48.185856 2.030637 +VERTEX_SE2 1734 18.348960 -47.294417 2.021685 +VERTEX_SE2 1735 17.931444 -46.408236 2.007468 +VERTEX_SE2 1736 17.031243 -46.855336 -2.723342 +VERTEX_SE2 1737 16.095539 -47.302479 -2.712911 +VERTEX_SE2 1738 15.162336 -47.732502 -2.737715 +VERTEX_SE2 1739 14.225397 -48.122600 -2.700669 +VERTEX_SE2 1740 13.317946 -48.548021 -2.720371 +VERTEX_SE2 1741 12.436837 -48.939749 -2.768126 +VERTEX_SE2 1742 11.481592 -49.293576 -2.753757 +VERTEX_SE2 1743 10.569249 -49.618382 -2.780975 +VERTEX_SE2 1744 10.207644 -48.685395 1.920445 +VERTEX_SE2 1745 9.892123 -47.736432 1.895054 +VERTEX_SE2 1746 9.576008 -46.849084 1.894719 +VERTEX_SE2 1747 9.242917 -45.934522 1.884332 +VERTEX_SE2 1748 8.894928 -45.018212 1.884236 +VERTEX_SE2 1749 8.555065 -44.073379 1.873012 +VERTEX_SE2 1750 8.238793 -43.128673 1.892632 +VERTEX_SE2 1751 7.902927 -42.174152 1.893919 +VERTEX_SE2 1752 8.836378 -41.846909 0.350069 +VERTEX_SE2 1753 9.750914 -41.474853 0.358459 +VERTEX_SE2 1754 10.672028 -41.152576 0.352082 +VERTEX_SE2 1755 11.603205 -40.806682 0.359049 +VERTEX_SE2 1756 11.931558 -41.743518 -1.197841 +VERTEX_SE2 1757 12.301522 -42.667770 -1.151024 +VERTEX_SE2 1758 12.720754 -43.601922 -1.117028 +VERTEX_SE2 1759 13.150497 -44.486285 -1.103115 +VERTEX_SE2 1760 12.270742 -44.961099 -2.671365 +VERTEX_SE2 1761 11.414233 -45.406193 -2.680104 +VERTEX_SE2 1762 10.518263 -45.892483 -2.648554 +VERTEX_SE2 1763 9.642786 -46.363484 -2.652183 +VERTEX_SE2 1764 10.098456 -47.222316 -1.098813 +VERTEX_SE2 1765 10.588967 -48.098902 -1.099938 +VERTEX_SE2 1766 11.049235 -48.978342 -1.096155 +VERTEX_SE2 1767 11.451732 -49.849528 -1.081808 +VERTEX_SE2 1768 10.597132 -50.325886 -2.641818 +VERTEX_SE2 1769 9.740275 -50.785972 -2.629279 +VERTEX_SE2 1770 8.841951 -51.272920 -2.609249 +VERTEX_SE2 1771 7.947247 -51.761687 -2.603799 +VERTEX_SE2 1772 8.764487 -51.236098 0.559101 +VERTEX_SE2 1773 9.611153 -50.718639 0.560736 +VERTEX_SE2 1774 10.454034 -50.179809 0.541926 +VERTEX_SE2 1775 11.339870 -49.653315 0.560148 +VERTEX_SE2 1776 11.919332 -50.470099 -1.029152 +VERTEX_SE2 1777 12.355546 -51.319567 -1.020402 +VERTEX_SE2 1778 12.895150 -52.187886 -1.001637 +VERTEX_SE2 1779 13.455257 -53.041487 -1.056190 +VERTEX_SE2 1780 14.296048 -52.570832 0.505350 +VERTEX_SE2 1781 15.136548 -52.112063 0.473335 +VERTEX_SE2 1782 15.983760 -51.656468 0.512331 +VERTEX_SE2 1783 16.820286 -51.161078 0.549832 +VERTEX_SE2 1784 17.370137 -52.007605 -1.044108 +VERTEX_SE2 1785 17.876519 -52.825405 -1.019672 +VERTEX_SE2 1786 18.364603 -53.662956 -0.990987 +VERTEX_SE2 1787 18.941376 -54.546025 -1.011594 +VERTEX_SE2 1788 19.791232 -54.017581 0.554596 +VERTEX_SE2 1789 20.616730 -53.470330 0.612568 +VERTEX_SE2 1790 21.427167 -52.921202 0.631534 +VERTEX_SE2 1791 22.248336 -52.351358 0.608581 +VERTEX_SE2 1792 21.427345 -52.907345 -2.512089 +VERTEX_SE2 1793 20.602306 -53.496370 -2.519125 +VERTEX_SE2 1794 19.768904 -54.085690 -2.500738 +VERTEX_SE2 1795 18.951506 -54.643054 -2.484997 +VERTEX_SE2 1796 19.735411 -54.034689 0.639693 +VERTEX_SE2 1797 20.565210 -53.449246 0.612026 +VERTEX_SE2 1798 21.375398 -52.873458 0.605107 +VERTEX_SE2 1799 22.186754 -52.317273 0.655251 +VERTEX_SE2 1800 21.572701 -51.559018 2.223821 +VERTEX_SE2 1801 20.975446 -50.735155 2.254765 +VERTEX_SE2 1802 20.348018 -49.969656 2.235695 +VERTEX_SE2 1803 19.738077 -49.203667 2.272362 +VERTEX_SE2 1804 18.952851 -49.815467 -2.440628 +VERTEX_SE2 1805 18.177638 -50.479166 -2.438904 +VERTEX_SE2 1806 17.415344 -51.146546 -2.424427 +VERTEX_SE2 1807 16.681144 -51.797973 -2.458635 +VERTEX_SE2 1808 16.055991 -51.035449 2.232825 +VERTEX_SE2 1809 15.412905 -50.240691 2.232738 +VERTEX_SE2 1810 14.800165 -49.449464 2.255608 +VERTEX_SE2 1811 14.180325 -48.669288 2.259598 +VERTEX_SE2 1812 13.518212 -47.894280 2.297883 +VERTEX_SE2 1813 12.823483 -47.148240 2.290972 +VERTEX_SE2 1814 12.183433 -46.419486 2.334427 +VERTEX_SE2 1815 11.466704 -45.662551 2.330780 +VERTEX_SE2 1816 12.181392 -44.984597 0.765020 +VERTEX_SE2 1817 12.867840 -44.326239 0.738145 +VERTEX_SE2 1818 13.624972 -43.649667 0.709443 +VERTEX_SE2 1819 14.377376 -42.999834 0.731590 +VERTEX_SE2 1820 13.634293 -43.659880 -2.390940 +VERTEX_SE2 1821 12.871703 -44.336217 -2.337845 +VERTEX_SE2 1822 12.215336 -45.029328 -2.358349 +VERTEX_SE2 1823 11.472304 -45.708082 -2.373501 +VERTEX_SE2 1824 10.761722 -44.966098 2.335759 +VERTEX_SE2 1825 10.061041 -44.268556 2.327799 +VERTEX_SE2 1826 9.370805 -43.541475 2.301068 +VERTEX_SE2 1827 8.705992 -42.770673 2.305912 +VERTEX_SE2 1828 9.372938 -43.502268 -0.827268 +VERTEX_SE2 1829 10.061836 -44.238464 -0.822224 +VERTEX_SE2 1830 10.771996 -44.962768 -0.830586 +VERTEX_SE2 1831 11.432714 -45.714310 -0.823889 +VERTEX_SE2 1832 12.178018 -45.016827 0.740531 +VERTEX_SE2 1833 12.903688 -44.312382 0.777336 +VERTEX_SE2 1834 13.588363 -43.614109 0.756732 +VERTEX_SE2 1835 14.343274 -42.929021 0.766555 +VERTEX_SE2 1836 13.673406 -42.233578 2.314935 +VERTEX_SE2 1837 12.966821 -41.456108 2.357918 +VERTEX_SE2 1838 12.256317 -40.766603 2.372821 +VERTEX_SE2 1839 11.562091 -40.093128 2.406591 +VERTEX_SE2 1840 10.949197 -40.818830 -2.317759 +VERTEX_SE2 1841 10.260867 -41.572364 -2.294797 +VERTEX_SE2 1842 9.628640 -42.320247 -2.343188 +VERTEX_SE2 1843 8.978860 -43.031055 -2.383295 +VERTEX_SE2 1844 8.234176 -43.758252 -2.389330 +VERTEX_SE2 1845 7.493635 -44.438807 -2.370747 +VERTEX_SE2 1846 6.787878 -45.135624 -2.332788 +VERTEX_SE2 1847 6.120066 -45.840951 -2.333422 +VERTEX_SE2 1848 5.434788 -45.169179 2.391848 +VERTEX_SE2 1849 4.720322 -44.495169 2.395857 +VERTEX_SE2 1850 3.973347 -43.822004 2.408350 +VERTEX_SE2 1851 3.237355 -43.169561 2.406742 +VERTEX_SE2 1852 2.572311 -43.928464 -2.296148 +VERTEX_SE2 1853 1.905799 -44.661956 -2.286050 +VERTEX_SE2 1854 1.232819 -45.414510 -2.273891 +VERTEX_SE2 1855 0.589232 -46.186264 -2.253037 +VERTEX_SE2 1856 -0.158204 -45.564867 2.455153 +VERTEX_SE2 1857 -0.948057 -44.931084 2.462612 +VERTEX_SE2 1858 -1.705993 -44.334574 2.511444 +VERTEX_SE2 1859 -2.485585 -43.748710 2.500606 +VERTEX_SE2 1860 -1.717981 -44.355125 -0.660064 +VERTEX_SE2 1861 -0.875611 -44.967742 -0.677391 +VERTEX_SE2 1862 -0.102638 -45.594446 -0.656849 +VERTEX_SE2 1863 0.727116 -46.194997 -0.644693 +VERTEX_SE2 1864 1.298234 -45.383363 0.956247 +VERTEX_SE2 1865 1.899396 -44.570904 0.940534 +VERTEX_SE2 1866 2.485518 -43.807880 0.960054 +VERTEX_SE2 1867 3.084312 -43.012099 0.970838 +VERTEX_SE2 1868 2.226293 -42.402550 2.551318 +VERTEX_SE2 1869 1.418095 -41.862840 2.569923 +VERTEX_SE2 1870 0.578975 -41.307183 2.569492 +VERTEX_SE2 1871 -0.269087 -40.754433 2.553491 +VERTEX_SE2 1872 0.265850 -39.932689 0.968241 +VERTEX_SE2 1873 0.815598 -39.126934 0.972014 +VERTEX_SE2 1874 1.386225 -38.352531 0.996910 +VERTEX_SE2 1875 1.936597 -37.491153 1.022605 +VERTEX_SE2 1876 1.101323 -36.965060 2.577445 +VERTEX_SE2 1877 0.253014 -36.416148 2.590072 +VERTEX_SE2 1878 -0.598812 -35.886103 2.559357 +VERTEX_SE2 1879 -1.363559 -35.337803 2.567652 +VERTEX_SE2 1880 -1.882270 -36.179482 -2.131078 +VERTEX_SE2 1881 -2.427040 -37.039688 -2.138690 +VERTEX_SE2 1882 -2.988804 -37.837529 -2.109677 +VERTEX_SE2 1883 -3.509448 -38.730716 -2.114153 +VERTEX_SE2 1884 -2.996899 -37.815429 1.003517 +VERTEX_SE2 1885 -2.466149 -36.951442 0.994688 +VERTEX_SE2 1886 -1.933994 -36.092844 0.990485 +VERTEX_SE2 1887 -1.395735 -35.241430 1.007897 +VERTEX_SE2 1888 -2.228271 -34.704690 2.558127 +VERTEX_SE2 1889 -3.098820 -34.120383 2.554320 +VERTEX_SE2 1890 -3.872923 -33.529142 2.554335 +VERTEX_SE2 1891 -4.729811 -32.939097 2.556704 +VERTEX_SE2 1892 -4.192114 -32.093718 0.983964 +VERTEX_SE2 1893 -3.651158 -31.238993 1.008280 +VERTEX_SE2 1894 -3.104791 -30.395406 1.039528 +VERTEX_SE2 1895 -2.556481 -29.559253 1.026917 +VERTEX_SE2 1896 -1.709730 -30.086817 -0.524553 +VERTEX_SE2 1897 -0.905055 -30.585936 -0.500376 +VERTEX_SE2 1898 -0.018270 -31.036558 -0.496294 +VERTEX_SE2 1899 0.876488 -31.550852 -0.542710 +VERTEX_SE2 1900 -0.033464 -31.024194 2.617800 +VERTEX_SE2 1901 -0.884610 -30.561710 2.593761 +VERTEX_SE2 1902 -1.748281 -30.028449 2.612683 +VERTEX_SE2 1903 -2.622151 -29.488038 2.616193 +VERTEX_SE2 1904 -2.131979 -28.615075 1.065973 +VERTEX_SE2 1905 -1.654514 -27.745563 1.050228 +VERTEX_SE2 1906 -1.159587 -26.911049 1.055220 +VERTEX_SE2 1907 -0.656048 -26.034234 1.057499 +VERTEX_SE2 1908 -1.572146 -25.490525 2.619549 +VERTEX_SE2 1909 -2.417216 -24.982475 2.600087 +VERTEX_SE2 1910 -3.329136 -24.480220 2.582200 +VERTEX_SE2 1911 -4.147220 -23.959870 2.581549 +VERTEX_SE2 1912 -4.652793 -24.824448 -2.120321 +VERTEX_SE2 1913 -5.181864 -25.680897 -2.130206 +VERTEX_SE2 1914 -5.726070 -26.534535 -2.160435 +VERTEX_SE2 1915 -6.268492 -27.352215 -2.171565 +VERTEX_SE2 1916 -5.427531 -27.909377 -0.580315 +VERTEX_SE2 1917 -4.598050 -28.460313 -0.557696 +VERTEX_SE2 1918 -3.759906 -29.023287 -0.557064 +VERTEX_SE2 1919 -2.934656 -29.584733 -0.577758 +VERTEX_SE2 1920 -3.486301 -30.470612 -2.155758 +VERTEX_SE2 1921 -4.055174 -31.313035 -2.142948 +VERTEX_SE2 1922 -4.570535 -32.168086 -2.136639 +VERTEX_SE2 1923 -5.060285 -33.003664 -2.171376 +VERTEX_SE2 1924 -4.239932 -33.559689 -0.646776 +VERTEX_SE2 1925 -3.421537 -34.164327 -0.655452 +VERTEX_SE2 1926 -2.677296 -34.811839 -0.617628 +VERTEX_SE2 1927 -1.881283 -35.357052 -0.602914 +VERTEX_SE2 1928 -2.469491 -36.170358 -2.185984 +VERTEX_SE2 1929 -3.089468 -36.988996 -2.170761 +VERTEX_SE2 1930 -3.673583 -37.861906 -2.197238 +VERTEX_SE2 1931 -4.206920 -38.662745 -2.202249 +VERTEX_SE2 1932 -5.023682 -38.090004 2.479751 +VERTEX_SE2 1933 -5.852540 -37.494897 2.503196 +VERTEX_SE2 1934 -6.675205 -36.878146 2.472380 +VERTEX_SE2 1935 -7.508595 -36.305594 2.512416 +VERTEX_SE2 1936 -6.691582 -36.875546 -0.611474 +VERTEX_SE2 1937 -5.864868 -37.415992 -0.594455 +VERTEX_SE2 1938 -4.996898 -37.985856 -0.606602 +VERTEX_SE2 1939 -4.203456 -38.576550 -0.610988 +VERTEX_SE2 1940 -3.387490 -39.183646 -0.596202 +VERTEX_SE2 1941 -2.570834 -39.729173 -0.584125 +VERTEX_SE2 1942 -1.726931 -40.268569 -0.610293 +VERTEX_SE2 1943 -0.910264 -40.817014 -0.620902 +VERTEX_SE2 1944 -0.092257 -41.367859 -0.592245 +VERTEX_SE2 1945 0.756494 -41.930518 -0.557013 +VERTEX_SE2 1946 1.585523 -42.458548 -0.563391 +VERTEX_SE2 1947 2.434010 -42.989087 -0.603728 +VERTEX_SE2 1948 3.027092 -42.122424 0.987682 +VERTEX_SE2 1949 3.574613 -41.298967 0.997331 +VERTEX_SE2 1950 4.134534 -40.461949 1.003608 +VERTEX_SE2 1951 4.684916 -39.617619 1.022793 +VERTEX_SE2 1952 5.540992 -40.109960 -0.550747 +VERTEX_SE2 1953 6.347977 -40.611147 -0.519596 +VERTEX_SE2 1954 7.200890 -41.131997 -0.495340 +VERTEX_SE2 1955 8.098565 -41.680791 -0.472715 +VERTEX_SE2 1956 8.571662 -40.840262 1.123425 +VERTEX_SE2 1957 8.953692 -39.982779 1.120031 +VERTEX_SE2 1958 9.345319 -39.063836 1.118147 +VERTEX_SE2 1959 9.795933 -38.176315 1.160461 +VERTEX_SE2 1960 8.882904 -37.761630 2.760761 +VERTEX_SE2 1961 7.895504 -37.400173 2.734117 +VERTEX_SE2 1962 6.982567 -36.984041 2.739352 +VERTEX_SE2 1963 6.094716 -36.572218 2.736679 +VERTEX_SE2 1964 7.009361 -36.984962 -0.349191 +VERTEX_SE2 1965 7.935689 -37.300961 -0.367740 +VERTEX_SE2 1966 8.899809 -37.636445 -0.356056 +VERTEX_SE2 1967 9.826365 -37.986927 -0.361515 +VERTEX_SE2 1968 9.471776 -38.884308 -1.957505 +VERTEX_SE2 1969 9.077462 -39.809679 -1.955223 +VERTEX_SE2 1970 8.696576 -40.747138 -1.946625 +VERTEX_SE2 1971 8.294528 -41.659739 -1.950634 +VERTEX_SE2 1972 8.673749 -40.771795 1.154856 +VERTEX_SE2 1973 9.109631 -39.847790 1.124369 +VERTEX_SE2 1974 9.559330 -38.965969 1.125982 +VERTEX_SE2 1975 9.981041 -38.062199 1.128050 +VERTEX_SE2 1976 9.086173 -37.620440 2.666150 +VERTEX_SE2 1977 8.187382 -37.189141 2.621716 +VERTEX_SE2 1978 7.307237 -36.667838 2.619420 +VERTEX_SE2 1979 6.419289 -36.186363 2.624259 +VERTEX_SE2 1980 6.931610 -35.298896 1.084799 +VERTEX_SE2 1981 7.387599 -34.429693 1.059095 +VERTEX_SE2 1982 7.894789 -33.558782 1.031247 +VERTEX_SE2 1983 8.423419 -32.706407 1.049630 +VERTEX_SE2 1984 9.304867 -33.201824 -0.521040 +VERTEX_SE2 1985 10.169217 -33.721685 -0.488807 +VERTEX_SE2 1986 11.062087 -34.212900 -0.458188 +VERTEX_SE2 1987 11.959454 -34.679755 -0.476758 +VERTEX_SE2 1988 12.871082 -35.148592 -0.501260 +VERTEX_SE2 1989 13.739786 -35.605421 -0.521306 +VERTEX_SE2 1990 14.614609 -36.124142 -0.546683 +VERTEX_SE2 1991 15.431817 -36.650051 -0.528829 +VERTEX_SE2 1992 14.567909 -36.105629 2.584491 +VERTEX_SE2 1993 13.746776 -35.563925 2.570070 +VERTEX_SE2 1994 12.922136 -35.021029 2.581645 +VERTEX_SE2 1995 12.056065 -34.511498 2.572226 +VERTEX_SE2 1996 11.541289 -35.382049 -2.109904 +VERTEX_SE2 1997 11.025785 -36.251269 -2.133898 +VERTEX_SE2 1998 10.516702 -37.082568 -2.161498 +VERTEX_SE2 1999 9.951899 -37.944498 -2.171743 +VERTEX_SE2 2000 9.383455 -38.758191 -2.199317 +VERTEX_SE2 2001 8.825215 -39.514939 -2.145884 +VERTEX_SE2 2002 8.250031 -40.415335 -2.142292 +VERTEX_SE2 2003 7.680140 -41.288285 -2.150796 +VERTEX_SE2 2004 8.203937 -40.425357 0.990284 +VERTEX_SE2 2005 8.768272 -39.596937 0.971345 +VERTEX_SE2 2006 9.346003 -38.773048 0.930845 +VERTEX_SE2 2007 9.933651 -37.945669 0.888262 +VERTEX_SE2 2008 9.306030 -38.743580 -2.271408 +VERTEX_SE2 2009 8.647835 -39.527075 -2.252013 +VERTEX_SE2 2010 8.061329 -40.314337 -2.257128 +VERTEX_SE2 2011 7.399955 -41.084636 -2.255374 +VERTEX_SE2 2012 8.004373 -40.311000 0.901806 +VERTEX_SE2 2013 8.592187 -39.526880 0.939454 +VERTEX_SE2 2014 9.187737 -38.712794 0.955628 +VERTEX_SE2 2015 9.703926 -37.907681 0.930791 +VERTEX_SE2 2016 10.528289 -38.535100 -0.589459 +VERTEX_SE2 2017 11.383427 -39.090861 -0.572633 +VERTEX_SE2 2018 12.242240 -39.627705 -0.560872 +VERTEX_SE2 2019 13.122645 -40.134977 -0.577944 +VERTEX_SE2 2020 12.631860 -40.941872 -2.157254 +VERTEX_SE2 2021 12.087991 -41.772965 -2.159433 +VERTEX_SE2 2022 11.520176 -42.577394 -2.158219 +VERTEX_SE2 2023 10.961682 -43.456848 -2.174320 +VERTEX_SE2 2024 11.786250 -44.033081 -0.586100 +VERTEX_SE2 2025 12.605586 -44.564680 -0.571955 +VERTEX_SE2 2026 13.448484 -45.139882 -0.544500 +VERTEX_SE2 2027 14.305361 -45.610151 -0.571762 +VERTEX_SE2 2028 13.471006 -45.089707 2.548928 +VERTEX_SE2 2029 12.654435 -44.526902 2.542878 +VERTEX_SE2 2030 11.806777 -43.946980 2.522321 +VERTEX_SE2 2031 11.008647 -43.306242 2.521197 +VERTEX_SE2 2032 11.577460 -42.488991 0.926387 +VERTEX_SE2 2033 12.192293 -41.671492 0.897899 +VERTEX_SE2 2034 12.802191 -40.892340 0.862452 +VERTEX_SE2 2035 13.413360 -40.105082 0.856804 +VERTEX_SE2 2036 12.664344 -39.429853 2.415184 +VERTEX_SE2 2037 11.908964 -38.730542 2.411893 +VERTEX_SE2 2038 11.178181 -38.049054 2.356285 +VERTEX_SE2 2039 10.488694 -37.350124 2.381859 +VERTEX_SE2 2040 11.206546 -38.068874 -0.723361 +VERTEX_SE2 2041 11.956617 -38.700295 -0.727761 +VERTEX_SE2 2042 12.688489 -39.339290 -0.691098 +VERTEX_SE2 2043 13.447568 -40.002146 -0.732148 +VERTEX_SE2 2044 12.772896 -40.757709 -2.286378 +VERTEX_SE2 2045 12.123117 -41.565379 -2.273342 +VERTEX_SE2 2046 11.493969 -42.255540 -2.289958 +VERTEX_SE2 2047 10.837111 -43.007548 -2.302642 +VERTEX_SE2 2048 11.519405 -42.263444 0.882978 +VERTEX_SE2 2049 12.150406 -41.469021 0.856439 +VERTEX_SE2 2050 12.801308 -40.701963 0.852249 +VERTEX_SE2 2051 13.435690 -39.985031 0.845281 +VERTEX_SE2 2052 14.168738 -40.644430 -0.756519 +VERTEX_SE2 2053 14.913164 -41.337313 -0.764464 +VERTEX_SE2 2054 15.563279 -42.053192 -0.738149 +VERTEX_SE2 2055 16.257406 -42.753817 -0.740717 +VERTEX_SE2 2056 15.518003 -42.086856 2.455343 +VERTEX_SE2 2057 14.767820 -41.471903 2.444002 +VERTEX_SE2 2058 14.013404 -40.824295 2.418058 +VERTEX_SE2 2059 13.238642 -40.153715 2.415661 +VERTEX_SE2 2060 13.982627 -40.822194 -0.749959 +VERTEX_SE2 2061 14.744943 -41.494647 -0.705115 +VERTEX_SE2 2062 15.463956 -42.125657 -0.726903 +VERTEX_SE2 2063 16.234353 -42.762618 -0.692461 +VERTEX_SE2 2064 15.609042 -43.495607 -2.276581 +VERTEX_SE2 2065 14.928799 -44.273364 -2.324082 +VERTEX_SE2 2066 14.204907 -45.014008 -2.307451 +VERTEX_SE2 2067 13.560967 -45.790620 -2.270005 +VERTEX_SE2 2068 14.216540 -45.027448 0.875495 +VERTEX_SE2 2069 14.837870 -44.281291 0.893698 +VERTEX_SE2 2070 15.430705 -43.537811 0.897167 +VERTEX_SE2 2071 16.083469 -42.732990 0.943274 +VERTEX_SE2 2072 16.898395 -43.328010 -0.624306 +VERTEX_SE2 2073 17.754009 -43.876295 -0.615168 +VERTEX_SE2 2074 18.566379 -44.432913 -0.634054 +VERTEX_SE2 2075 19.384311 -45.051175 -0.622234 +VERTEX_SE2 2076 19.935469 -44.261399 0.971296 +VERTEX_SE2 2077 20.471936 -43.443544 0.988560 +VERTEX_SE2 2078 20.999135 -42.613271 0.987868 +VERTEX_SE2 2079 21.577373 -41.800045 1.005828 +VERTEX_SE2 2080 20.702713 -41.251271 2.573868 +VERTEX_SE2 2081 19.849039 -40.664762 2.605192 +VERTEX_SE2 2082 18.978739 -40.138566 2.610789 +VERTEX_SE2 2083 18.128653 -39.630755 2.567980 +VERTEX_SE2 2084 18.905315 -40.173675 -0.535020 +VERTEX_SE2 2085 19.735136 -40.664329 -0.582553 +VERTEX_SE2 2086 20.613659 -41.194867 -0.632050 +VERTEX_SE2 2087 21.442666 -41.746509 -0.575576 +VERTEX_SE2 2088 20.635838 -41.187068 2.555364 +VERTEX_SE2 2089 19.769981 -40.607496 2.573395 +VERTEX_SE2 2090 18.906483 -40.095948 2.567981 +VERTEX_SE2 2091 18.048614 -39.546099 2.537763 +VERTEX_SE2 2092 18.907085 -40.133762 -0.623117 +VERTEX_SE2 2093 19.698970 -40.692412 -0.643573 +VERTEX_SE2 2094 20.484246 -41.291044 -0.643139 +VERTEX_SE2 2095 21.320265 -41.944765 -0.657518 +VERTEX_SE2 2096 20.689168 -42.756986 -2.219028 +VERTEX_SE2 2097 20.100457 -43.532417 -2.199859 +VERTEX_SE2 2098 19.496358 -44.359294 -2.194331 +VERTEX_SE2 2099 18.870400 -45.209838 -2.204457 +VERTEX_SE2 2100 18.286637 -46.030501 -2.188592 +VERTEX_SE2 2101 17.707570 -46.850872 -2.203794 +VERTEX_SE2 2102 17.088720 -47.658977 -2.206992 +VERTEX_SE2 2103 16.487418 -48.436331 -2.218526 +VERTEX_SE2 2104 17.039468 -47.662480 0.907314 +VERTEX_SE2 2105 17.667197 -46.854900 0.923851 +VERTEX_SE2 2106 18.279989 -46.024702 0.919572 +VERTEX_SE2 2107 18.884732 -45.252249 0.902723 +VERTEX_SE2 2108 18.242338 -46.047306 -2.274877 +VERTEX_SE2 2109 17.569237 -46.805288 -2.260617 +VERTEX_SE2 2110 16.938082 -47.590361 -2.261297 +VERTEX_SE2 2111 16.288763 -48.358363 -2.251607 +VERTEX_SE2 2112 17.029501 -49.033791 -0.704917 +VERTEX_SE2 2113 17.819580 -49.675000 -0.700415 +VERTEX_SE2 2114 18.566661 -50.359432 -0.748145 +VERTEX_SE2 2115 19.291476 -51.074718 -0.724364 +VERTEX_SE2 2116 18.543163 -50.423729 2.425436 +VERTEX_SE2 2117 17.778831 -49.771124 2.403285 +VERTEX_SE2 2118 17.011919 -49.104675 2.412212 +VERTEX_SE2 2119 16.254510 -48.458967 2.411281 +VERTEX_SE2 2120 16.968836 -49.135856 -0.722419 +VERTEX_SE2 2121 17.733707 -49.805557 -0.727574 +VERTEX_SE2 2122 18.500353 -50.421595 -0.690209 +VERTEX_SE2 2123 19.324456 -51.041423 -0.708846 +VERTEX_SE2 2124 18.687712 -51.796985 -2.267606 +VERTEX_SE2 2125 18.029892 -52.572566 -2.259812 +VERTEX_SE2 2126 17.421780 -53.377940 -2.248516 +VERTEX_SE2 2127 16.760331 -54.144919 -2.282109 +VERTEX_SE2 2128 16.003089 -53.502597 2.437191 +VERTEX_SE2 2129 15.244686 -52.874461 2.439464 +VERTEX_SE2 2130 14.477583 -52.223343 2.485626 +VERTEX_SE2 2131 13.669086 -51.590825 2.483807 +VERTEX_SE2 2132 14.494531 -52.252238 -0.652943 +VERTEX_SE2 2133 15.307381 -52.838984 -0.659737 +VERTEX_SE2 2134 16.093771 -53.488249 -0.632092 +VERTEX_SE2 2135 16.928421 -54.086574 -0.589694 +VERTEX_SE2 2136 17.765915 -54.619775 -0.615152 +VERTEX_SE2 2137 18.546596 -55.128686 -0.607147 +VERTEX_SE2 2138 19.427097 -55.697078 -0.587908 +VERTEX_SE2 2139 20.282215 -56.259235 -0.587372 +VERTEX_SE2 2140 20.815315 -55.454434 0.994318 +VERTEX_SE2 2141 21.405438 -54.606247 0.981447 +VERTEX_SE2 2142 21.999966 -53.737515 0.976375 +VERTEX_SE2 2143 22.573323 -52.893331 0.951484 +VERTEX_SE2 2144 21.755483 -52.294390 2.492434 +VERTEX_SE2 2145 21.000831 -51.636756 2.474782 +VERTEX_SE2 2146 20.204515 -51.019670 2.470696 +VERTEX_SE2 2147 19.433934 -50.422957 2.486064 +VERTEX_SE2 2148 20.209415 -51.019135 -0.688646 +VERTEX_SE2 2149 21.026961 -51.637879 -0.714095 +VERTEX_SE2 2150 21.765650 -52.305304 -0.721034 +VERTEX_SE2 2151 22.555389 -52.992104 -0.699190 +VERTEX_SE2 2152 21.960533 -53.780077 -2.294170 +VERTEX_SE2 2153 21.290619 -54.534105 -2.275415 +VERTEX_SE2 2154 20.646698 -55.330925 -2.247805 +VERTEX_SE2 2155 19.988522 -56.108789 -2.228238 +VERTEX_SE2 2156 20.788851 -56.697932 -0.662708 +VERTEX_SE2 2157 21.550524 -57.308792 -0.655179 +VERTEX_SE2 2158 22.342590 -57.900667 -0.644368 +VERTEX_SE2 2159 23.133802 -58.497834 -0.655426 +VERTEX_SE2 2160 22.298653 -57.850918 2.478564 +VERTEX_SE2 2161 21.485910 -57.253505 2.498893 +VERTEX_SE2 2162 20.699568 -56.646422 2.510600 +VERTEX_SE2 2163 19.906112 -56.074781 2.505548 +VERTEX_SE2 2164 20.487996 -55.262349 0.952058 +VERTEX_SE2 2165 21.110016 -54.458181 0.986039 +VERTEX_SE2 2166 21.676047 -53.589805 0.977800 +VERTEX_SE2 2167 22.248560 -52.776329 1.005178 +VERTEX_SE2 2168 21.649581 -53.616564 -2.156262 +VERTEX_SE2 2169 21.060500 -54.480967 -2.196742 +VERTEX_SE2 2170 20.513346 -55.322137 -2.155338 +VERTEX_SE2 2171 19.926110 -56.156577 -2.179565 +VERTEX_SE2 2172 20.740559 -56.759672 -0.641425 +VERTEX_SE2 2173 21.550462 -57.375076 -0.642536 +VERTEX_SE2 2174 22.315989 -57.982022 -0.679791 +VERTEX_SE2 2175 23.074411 -58.591888 -0.657561 +VERTEX_SE2 2176 23.726200 -57.793195 0.900849 +VERTEX_SE2 2177 24.378307 -57.006088 0.887175 +VERTEX_SE2 2178 25.011148 -56.237762 0.860624 +VERTEX_SE2 2179 25.613118 -55.496782 0.856783 +VERTEX_SE2 2180 24.872030 -54.839136 2.349333 +VERTEX_SE2 2181 24.163454 -54.096350 2.337812 +VERTEX_SE2 2182 23.448582 -53.391117 2.362229 +VERTEX_SE2 2183 22.726384 -52.715802 2.359464 +VERTEX_SE2 2184 23.487956 -53.461683 -0.805466 +VERTEX_SE2 2185 24.186520 -54.158300 -0.770680 +VERTEX_SE2 2186 24.906897 -54.860767 -0.791735 +VERTEX_SE2 2187 25.584067 -55.553015 -0.785326 +VERTEX_SE2 2188 26.258316 -54.860431 0.801574 +VERTEX_SE2 2189 27.000151 -54.122779 0.773854 +VERTEX_SE2 2190 27.698953 -53.433132 0.780926 +VERTEX_SE2 2191 28.414796 -52.741795 0.806948 +VERTEX_SE2 2192 27.765004 -53.450726 -2.326262 +VERTEX_SE2 2193 27.059133 -54.183872 -2.373462 +VERTEX_SE2 2194 26.361931 -54.871237 -2.387830 +VERTEX_SE2 2195 25.627034 -55.566418 -2.372133 +VERTEX_SE2 2196 26.330213 -54.883137 0.774107 +VERTEX_SE2 2197 27.033190 -54.188949 0.763649 +VERTEX_SE2 2198 27.799619 -53.516854 0.733358 +VERTEX_SE2 2199 28.511965 -52.882317 0.753321 +VERTEX_SE2 2200 27.809695 -52.165404 2.358221 +VERTEX_SE2 2201 27.082188 -51.476198 2.360758 +VERTEX_SE2 2202 26.370526 -50.750275 2.344722 +VERTEX_SE2 2203 25.673401 -50.040229 2.371264 +VERTEX_SE2 2204 26.428834 -50.795601 -0.782986 +VERTEX_SE2 2205 27.146715 -51.520891 -0.763469 +VERTEX_SE2 2206 27.870852 -52.249557 -0.766234 +VERTEX_SE2 2207 28.619174 -52.960942 -0.770026 +VERTEX_SE2 2208 27.923341 -52.262643 2.354174 +VERTEX_SE2 2209 27.294150 -51.517052 2.363581 +VERTEX_SE2 2210 26.579874 -50.826773 2.367382 +VERTEX_SE2 2211 25.884401 -50.139370 2.363531 +VERTEX_SE2 2212 26.606110 -49.415924 0.823891 +VERTEX_SE2 2213 27.292914 -48.674199 0.828053 +VERTEX_SE2 2214 27.936462 -47.924806 0.825982 +VERTEX_SE2 2215 28.637778 -47.170368 0.837413 +VERTEX_SE2 2216 29.388222 -47.888643 -0.719847 +VERTEX_SE2 2217 30.136690 -48.541336 -0.693808 +VERTEX_SE2 2218 30.901391 -49.185579 -0.688361 +VERTEX_SE2 2219 31.644984 -49.832362 -0.661820 +VERTEX_SE2 2220 30.859819 -49.216052 2.471210 +VERTEX_SE2 2221 30.090252 -48.607477 2.450117 +VERTEX_SE2 2222 29.332515 -47.960374 2.415995 +VERTEX_SE2 2223 28.557412 -47.301884 2.421335 +VERTEX_SE2 2224 29.295423 -47.953164 -0.767715 +VERTEX_SE2 2225 29.995272 -48.607200 -0.708908 +VERTEX_SE2 2226 30.717072 -49.225194 -0.699257 +VERTEX_SE2 2227 31.421969 -49.853757 -0.674948 +VERTEX_SE2 2228 32.170014 -50.461167 -0.660961 +VERTEX_SE2 2229 32.927419 -51.089136 -0.655126 +VERTEX_SE2 2230 33.685178 -51.688789 -0.699907 +VERTEX_SE2 2231 34.486936 -52.289187 -0.717126 +VERTEX_SE2 2232 35.107662 -51.495904 0.861924 +VERTEX_SE2 2233 35.760940 -50.722682 0.882130 +VERTEX_SE2 2234 36.370763 -49.975438 0.899361 +VERTEX_SE2 2235 37.002324 -49.187909 0.909706 +VERTEX_SE2 2236 36.220039 -48.587747 2.469976 +VERTEX_SE2 2237 35.432494 -47.988464 2.489562 +VERTEX_SE2 2238 34.616205 -47.373056 2.499224 +VERTEX_SE2 2239 33.813582 -46.765928 2.536485 +VERTEX_SE2 2240 34.653601 -47.338212 -0.595785 +VERTEX_SE2 2241 35.470933 -47.919629 -0.578916 +VERTEX_SE2 2242 36.311669 -48.455907 -0.571687 +VERTEX_SE2 2243 37.158100 -49.019847 -0.525032 +VERTEX_SE2 2244 37.672746 -48.110416 1.017918 +VERTEX_SE2 2245 38.209059 -47.228011 0.998526 +VERTEX_SE2 2246 38.750098 -46.371383 0.993416 +VERTEX_SE2 2247 39.295148 -45.541902 1.006112 +VERTEX_SE2 2248 38.446180 -45.033732 2.583452 +VERTEX_SE2 2249 37.604104 -44.517462 2.525649 +VERTEX_SE2 2250 36.797229 -43.941154 2.549948 +VERTEX_SE2 2251 35.991882 -43.390358 2.573814 +VERTEX_SE2 2252 36.801268 -43.929108 -0.534706 +VERTEX_SE2 2253 37.625986 -44.425597 -0.519584 +VERTEX_SE2 2254 38.509924 -44.957821 -0.524695 +VERTEX_SE2 2255 39.359079 -45.462499 -0.536198 +VERTEX_SE2 2256 39.865956 -44.595990 1.082132 +VERTEX_SE2 2257 40.341637 -43.742281 1.081123 +VERTEX_SE2 2258 40.839257 -42.861497 1.048395 +VERTEX_SE2 2259 41.335610 -41.987775 1.061842 +VERTEX_SE2 2260 40.846198 -42.816081 -2.069608 +VERTEX_SE2 2261 40.386464 -43.698246 -2.098406 +VERTEX_SE2 2262 39.859642 -44.569716 -2.119148 +VERTEX_SE2 2263 39.341148 -45.415000 -2.091893 +VERTEX_SE2 2264 39.843728 -44.536800 1.061897 +VERTEX_SE2 2265 40.323053 -43.705083 1.042782 +VERTEX_SE2 2266 40.844792 -42.867043 1.032688 +VERTEX_SE2 2267 41.344687 -42.020732 1.059518 +VERTEX_SE2 2268 40.439332 -41.528038 2.597758 +VERTEX_SE2 2269 39.582789 -41.019990 2.584932 +VERTEX_SE2 2270 38.752611 -40.499349 2.569097 +VERTEX_SE2 2271 37.910775 -39.952006 2.563093 +VERTEX_SE2 2272 38.737911 -40.512923 -0.583507 +VERTEX_SE2 2273 39.534182 -41.056691 -0.595381 +VERTEX_SE2 2274 40.350223 -41.620981 -0.594052 +VERTEX_SE2 2275 41.186632 -42.175014 -0.589060 +VERTEX_SE2 2276 40.310729 -41.617203 2.549030 +VERTEX_SE2 2277 39.488634 -41.036470 2.569972 +VERTEX_SE2 2278 38.654821 -40.527389 2.610851 +VERTEX_SE2 2279 37.822241 -40.058868 2.615647 +VERTEX_SE2 2280 37.338671 -40.912951 -2.106543 +VERTEX_SE2 2281 36.838137 -41.758802 -2.140900 +VERTEX_SE2 2282 36.342302 -42.586418 -2.148686 +VERTEX_SE2 2283 35.800149 -43.425915 -2.151918 +VERTEX_SE2 2284 34.987266 -42.885362 2.573382 +VERTEX_SE2 2285 34.109040 -42.344886 2.566518 +VERTEX_SE2 2286 33.247422 -41.779924 2.613102 +VERTEX_SE2 2287 32.374049 -41.269577 2.624980 +VERTEX_SE2 2288 33.252987 -41.781029 -0.593120 +VERTEX_SE2 2289 34.070270 -42.335703 -0.580639 +VERTEX_SE2 2290 34.919822 -42.914674 -0.568847 +VERTEX_SE2 2291 35.734747 -43.432202 -0.516426 +VERTEX_SE2 2292 35.231649 -44.284293 -2.091286 +VERTEX_SE2 2293 34.719363 -45.137227 -2.083821 +VERTEX_SE2 2294 34.220202 -46.028156 -2.079737 +VERTEX_SE2 2295 33.740672 -46.908451 -2.074665 +VERTEX_SE2 2296 34.232018 -46.046596 1.077015 +VERTEX_SE2 2297 34.720479 -45.200955 1.075799 +VERTEX_SE2 2298 35.185658 -44.303166 1.092832 +VERTEX_SE2 2299 35.610335 -43.418639 1.076551 +VERTEX_SE2 2300 34.740278 -42.984575 2.658641 +VERTEX_SE2 2301 33.842540 -42.508110 2.637844 +VERTEX_SE2 2302 32.964517 -42.060529 2.606100 +VERTEX_SE2 2303 32.081831 -41.527600 2.587098 +VERTEX_SE2 2304 32.921726 -42.070719 -0.538232 +VERTEX_SE2 2305 33.786208 -42.606539 -0.547994 +VERTEX_SE2 2306 34.704256 -43.149981 -0.562075 +VERTEX_SE2 2307 35.539800 -43.690188 -0.544532 +VERTEX_SE2 2308 35.019004 -44.543969 -2.105432 +VERTEX_SE2 2309 34.506700 -45.448848 -2.129120 +VERTEX_SE2 2310 33.999941 -46.273039 -2.132954 +VERTEX_SE2 2311 33.474450 -47.122233 -2.129232 +VERTEX_SE2 2312 34.006833 -46.289472 0.958808 +VERTEX_SE2 2313 34.624660 -45.449883 0.977258 +VERTEX_SE2 2314 35.214984 -44.616926 0.963794 +VERTEX_SE2 2315 35.791071 -43.770374 0.976084 +VERTEX_SE2 2316 36.608187 -44.316971 -0.588456 +VERTEX_SE2 2317 37.408952 -44.888280 -0.608110 +VERTEX_SE2 2318 38.227476 -45.467912 -0.582767 +VERTEX_SE2 2319 39.072804 -46.018011 -0.584623 +VERTEX_SE2 2320 38.286862 -45.445420 2.596957 +VERTEX_SE2 2321 37.477538 -44.923250 2.575924 +VERTEX_SE2 2322 36.607718 -44.387817 2.585038 +VERTEX_SE2 2323 35.761045 -43.877349 2.585316 +VERTEX_SE2 2324 35.231654 -44.672517 -2.144884 +VERTEX_SE2 2325 34.701492 -45.516852 -2.156295 +VERTEX_SE2 2326 34.161398 -46.331318 -2.158023 +VERTEX_SE2 2327 33.617494 -47.166078 -2.167796 +VERTEX_SE2 2328 34.175695 -46.357499 0.997864 +VERTEX_SE2 2329 34.726222 -45.526455 0.984231 +VERTEX_SE2 2330 35.331886 -44.690392 0.983374 +VERTEX_SE2 2331 35.877502 -43.830536 0.993498 +VERTEX_SE2 2332 36.702870 -44.346683 -0.567922 +VERTEX_SE2 2333 37.555937 -44.875158 -0.547239 +VERTEX_SE2 2334 38.412678 -45.389698 -0.536131 +VERTEX_SE2 2335 39.281915 -45.922465 -0.548921 +VERTEX_SE2 2336 38.433264 -45.410901 2.593119 +VERTEX_SE2 2337 37.538179 -44.867034 2.581777 +VERTEX_SE2 2338 36.684713 -44.358847 2.598179 +VERTEX_SE2 2339 35.816783 -43.890633 2.619296 +VERTEX_SE2 2340 36.676616 -44.410994 -0.558754 +VERTEX_SE2 2341 37.520258 -44.887465 -0.543456 +VERTEX_SE2 2342 38.351193 -45.405771 -0.575879 +VERTEX_SE2 2343 39.215663 -45.929389 -0.616795 +VERTEX_SE2 2344 39.761049 -45.158493 0.950795 +VERTEX_SE2 2345 40.345881 -44.332913 0.991657 +VERTEX_SE2 2346 40.897697 -43.501290 1.008139 +VERTEX_SE2 2347 41.383986 -42.667023 1.021338 +VERTEX_SE2 2348 40.526890 -42.153280 2.593218 +VERTEX_SE2 2349 39.636605 -41.635508 2.613090 +VERTEX_SE2 2350 38.756157 -41.107887 2.589667 +VERTEX_SE2 2351 37.896585 -40.576503 2.586664 +VERTEX_SE2 2352 38.416010 -39.720353 1.036534 +VERTEX_SE2 2353 38.955708 -38.873671 1.023479 +VERTEX_SE2 2354 39.466940 -38.016562 1.028665 +VERTEX_SE2 2355 39.992958 -37.189796 1.084570 +VERTEX_SE2 2356 39.554557 -38.105638 -2.101100 +VERTEX_SE2 2357 39.049593 -38.974818 -2.095774 +VERTEX_SE2 2358 38.557924 -39.828393 -2.068957 +VERTEX_SE2 2359 38.081854 -40.692363 -2.081498 +VERTEX_SE2 2360 38.965198 -41.177254 -0.535778 +VERTEX_SE2 2361 39.798359 -41.729823 -0.514871 +VERTEX_SE2 2362 40.700338 -42.224270 -0.493434 +VERTEX_SE2 2363 41.598436 -42.688545 -0.498015 +VERTEX_SE2 2364 41.099420 -43.587281 -2.047025 +VERTEX_SE2 2365 40.652967 -44.481130 -2.046742 +VERTEX_SE2 2366 40.193209 -45.369053 -2.027874 +VERTEX_SE2 2367 39.769061 -46.253731 -2.085001 +VERTEX_SE2 2368 40.237709 -45.416692 1.059479 +VERTEX_SE2 2369 40.739220 -44.522406 1.038987 +VERTEX_SE2 2370 41.262111 -43.688271 1.049021 +VERTEX_SE2 2371 41.742275 -42.795475 1.070427 +VERTEX_SE2 2372 40.845710 -42.307201 2.634547 +VERTEX_SE2 2373 39.963157 -41.862736 2.638729 +VERTEX_SE2 2374 39.078303 -41.362867 2.612249 +VERTEX_SE2 2375 38.253115 -40.884428 2.630630 +VERTEX_SE2 2376 37.802245 -41.774511 -2.040200 +VERTEX_SE2 2377 37.365362 -42.676036 -2.062091 +VERTEX_SE2 2378 36.877942 -43.571103 -2.066941 +VERTEX_SE2 2379 36.389791 -44.455399 -2.073325 +VERTEX_SE2 2380 37.271229 -44.917553 -0.513935 +VERTEX_SE2 2381 38.150727 -45.434058 -0.513851 +VERTEX_SE2 2382 39.009587 -45.929247 -0.492316 +VERTEX_SE2 2383 39.867584 -46.424611 -0.487269 +VERTEX_SE2 2384 40.357853 -45.512721 1.042741 +VERTEX_SE2 2385 40.857630 -44.625438 1.061068 +VERTEX_SE2 2386 41.337035 -43.752757 1.043794 +VERTEX_SE2 2387 41.847671 -42.880916 1.042479 +VERTEX_SE2 2388 41.023688 -42.351352 2.621309 +VERTEX_SE2 2389 40.131671 -41.842112 2.624311 +VERTEX_SE2 2390 39.251566 -41.306900 2.625503 +VERTEX_SE2 2391 38.395140 -40.803828 2.632791 +VERTEX_SE2 2392 38.886523 -39.933239 1.058161 +VERTEX_SE2 2393 39.351559 -39.018790 1.092174 +VERTEX_SE2 2394 39.838621 -38.105358 1.097973 +VERTEX_SE2 2395 40.295484 -37.211573 1.094259 +VERTEX_SE2 2396 39.836033 -38.090450 -2.097811 +VERTEX_SE2 2397 39.345575 -38.943418 -2.125998 +VERTEX_SE2 2398 38.835159 -39.789766 -2.124933 +VERTEX_SE2 2399 38.297827 -40.684770 -2.106022 +VERTEX_SE2 2400 39.112195 -41.176538 -0.523282 +VERTEX_SE2 2401 39.975389 -41.696476 -0.495889 +VERTEX_SE2 2402 40.829789 -42.198790 -0.460867 +VERTEX_SE2 2403 41.707771 -42.640608 -0.450582 +VERTEX_SE2 2404 41.267196 -43.562236 -2.049522 +VERTEX_SE2 2405 40.827579 -44.479561 -2.038943 +VERTEX_SE2 2406 40.366888 -45.383018 -2.027871 +VERTEX_SE2 2407 39.923106 -46.263725 -1.989311 +VERTEX_SE2 2408 39.511104 -47.147705 -2.007948 +VERTEX_SE2 2409 39.089351 -48.042722 -2.005181 +VERTEX_SE2 2410 38.676948 -48.940509 -2.024058 +VERTEX_SE2 2411 38.279273 -49.834867 -2.042849 +VERTEX_SE2 2412 37.404124 -49.407797 2.675341 +VERTEX_SE2 2413 36.508786 -48.901679 2.661033 +VERTEX_SE2 2414 35.618097 -48.431042 2.669604 +VERTEX_SE2 2415 34.716300 -47.988533 2.630713 +VERTEX_SE2 2416 35.211922 -47.118711 1.080703 +VERTEX_SE2 2417 35.723440 -46.265508 1.044123 +VERTEX_SE2 2418 36.229032 -45.391820 1.052598 +VERTEX_SE2 2419 36.703475 -44.565933 1.032461 +VERTEX_SE2 2420 37.556927 -45.055311 -0.570539 +VERTEX_SE2 2421 38.394367 -45.598206 -0.555575 +VERTEX_SE2 2422 39.210992 -46.129434 -0.599864 +VERTEX_SE2 2423 40.029378 -46.691903 -0.620881 +VERTEX_SE2 2424 39.442562 -47.525141 -2.183181 +VERTEX_SE2 2425 38.900030 -48.363323 -2.173823 +VERTEX_SE2 2426 38.337749 -49.182278 -2.159724 +VERTEX_SE2 2427 37.776843 -49.986300 -2.138849 +VERTEX_SE2 2428 38.347037 -49.145526 1.001161 +VERTEX_SE2 2429 38.907412 -48.300819 1.020410 +VERTEX_SE2 2430 39.420456 -47.441790 1.063471 +VERTEX_SE2 2431 39.871582 -46.570715 1.025707 +VERTEX_SE2 2432 39.005481 -46.090240 2.627097 +VERTEX_SE2 2433 38.165762 -45.654444 2.638175 +VERTEX_SE2 2434 37.253285 -45.160819 2.668555 +VERTEX_SE2 2435 36.340019 -44.717107 2.667015 +VERTEX_SE2 2436 36.756212 -43.860063 1.159855 +VERTEX_SE2 2437 37.152051 -42.933761 1.129897 +VERTEX_SE2 2438 37.584096 -42.037619 1.118814 +VERTEX_SE2 2439 38.011704 -41.161599 1.110025 +VERTEX_SE2 2440 37.573191 -42.080077 -2.021535 +VERTEX_SE2 2441 37.080719 -42.923546 -2.024155 +VERTEX_SE2 2442 36.653552 -43.833204 -2.021325 +VERTEX_SE2 2443 36.191861 -44.760548 -2.016927 +VERTEX_SE2 2444 36.622935 -43.860561 1.129073 +VERTEX_SE2 2445 37.012254 -42.955007 1.150344 +VERTEX_SE2 2446 37.452995 -42.070632 1.165258 +VERTEX_SE2 2447 37.823845 -41.177896 1.156893 +VERTEX_SE2 2448 36.899044 -40.755127 2.720523 +VERTEX_SE2 2449 35.942033 -40.349019 2.714356 +VERTEX_SE2 2450 34.977651 -39.937146 2.772728 +VERTEX_SE2 2451 34.065904 -39.589896 2.742993 +VERTEX_SE2 2452 34.474912 -38.698105 1.179833 +VERTEX_SE2 2453 34.858769 -37.780497 1.221240 +VERTEX_SE2 2454 35.191879 -36.823943 1.232052 +VERTEX_SE2 2455 35.523373 -35.877908 1.233907 +VERTEX_SE2 2456 36.412167 -36.199516 -0.369533 +VERTEX_SE2 2457 37.310320 -36.582054 -0.364536 +VERTEX_SE2 2458 38.231117 -36.931912 -0.357923 +VERTEX_SE2 2459 39.159625 -37.300703 -0.333692 +VERTEX_SE2 2460 38.181200 -37.009055 2.797898 +VERTEX_SE2 2461 37.254304 -36.702081 2.790266 +VERTEX_SE2 2462 36.257091 -36.341069 2.773756 +VERTEX_SE2 2463 35.340844 -35.977349 2.780162 +VERTEX_SE2 2464 35.718881 -35.010630 1.223852 +VERTEX_SE2 2465 36.067515 -34.070562 1.265852 +VERTEX_SE2 2466 36.354286 -33.101975 1.270598 +VERTEX_SE2 2467 36.662823 -32.158868 1.275644 +VERTEX_SE2 2468 37.622088 -32.452026 -0.304236 +VERTEX_SE2 2469 38.601824 -32.752622 -0.308299 +VERTEX_SE2 2470 39.578329 -33.040476 -0.279321 +VERTEX_SE2 2471 40.550412 -33.302253 -0.272367 +VERTEX_SE2 2472 39.569165 -32.997453 2.855273 +VERTEX_SE2 2473 38.635646 -32.708248 2.858131 +VERTEX_SE2 2474 37.697159 -32.408500 2.901426 +VERTEX_SE2 2475 36.743773 -32.197618 2.868394 +VERTEX_SE2 2476 37.041287 -31.236672 1.271824 +VERTEX_SE2 2477 37.307126 -30.302129 1.266805 +VERTEX_SE2 2478 37.576622 -29.338264 1.255912 +VERTEX_SE2 2479 37.915380 -28.405426 1.280161 +VERTEX_SE2 2480 36.959238 -28.099043 2.844941 +VERTEX_SE2 2481 35.985263 -27.806941 2.847923 +VERTEX_SE2 2482 35.004870 -27.531435 2.851514 +VERTEX_SE2 2483 34.040583 -27.241326 2.860867 +VERTEX_SE2 2484 35.006047 -27.543575 -0.271063 +VERTEX_SE2 2485 35.987592 -27.778357 -0.275594 +VERTEX_SE2 2486 36.931211 -28.036751 -0.307519 +VERTEX_SE2 2487 37.868438 -28.335179 -0.293151 +VERTEX_SE2 2488 36.885856 -28.045265 2.850969 +VERTEX_SE2 2489 35.886660 -27.786129 2.837011 +VERTEX_SE2 2490 34.962180 -27.485904 2.817767 +VERTEX_SE2 2491 34.054501 -27.135860 2.859331 +VERTEX_SE2 2492 35.016238 -27.386884 -0.253619 +VERTEX_SE2 2493 36.010865 -27.635223 -0.252633 +VERTEX_SE2 2494 37.003219 -27.878692 -0.240757 +VERTEX_SE2 2495 37.948085 -28.148849 -0.250851 +VERTEX_SE2 2496 38.162447 -27.183905 1.315179 +VERTEX_SE2 2497 38.422187 -26.221849 1.346021 +VERTEX_SE2 2498 38.655746 -25.264781 1.352673 +VERTEX_SE2 2499 38.846413 -24.333740 1.361786 +VERTEX_SE2 2500 37.919075 -24.113230 2.914736 +VERTEX_SE2 2501 36.973397 -23.886479 2.894740 +VERTEX_SE2 2502 35.979933 -23.663229 2.934183 +VERTEX_SE2 2503 35.001493 -23.473033 2.902679 +VERTEX_SE2 2504 35.228995 -22.525606 1.332249 +VERTEX_SE2 2505 35.450636 -21.553267 1.300984 +VERTEX_SE2 2506 35.705150 -20.629003 1.314293 +VERTEX_SE2 2507 35.989067 -19.686720 1.301738 +VERTEX_SE2 2508 35.010154 -19.416967 2.860348 +VERTEX_SE2 2509 34.054310 -19.148979 2.901060 +VERTEX_SE2 2510 33.074556 -18.923380 2.929825 +VERTEX_SE2 2511 32.097151 -18.748469 2.928991 +VERTEX_SE2 2512 32.297412 -17.769125 1.336341 +VERTEX_SE2 2513 32.495438 -16.832619 1.331009 +VERTEX_SE2 2514 32.736673 -15.831765 1.305549 +VERTEX_SE2 2515 32.957339 -14.881376 1.306259 +VERTEX_SE2 2516 33.211778 -13.938581 1.313439 +VERTEX_SE2 2517 33.487108 -12.977010 1.281850 +VERTEX_SE2 2518 33.760647 -12.008482 1.275581 +VERTEX_SE2 2519 34.022489 -11.038690 1.256870 +VERTEX_SE2 2520 34.959906 -11.355593 -0.325310 +VERTEX_SE2 2521 35.869550 -11.648742 -0.317156 +VERTEX_SE2 2522 36.807384 -11.928290 -0.310276 +VERTEX_SE2 2523 37.778564 -12.242531 -0.304988 +VERTEX_SE2 2524 37.504297 -13.247608 -1.862578 +VERTEX_SE2 2525 37.239101 -14.214833 -1.891150 +VERTEX_SE2 2526 36.954657 -15.181480 -1.910991 +VERTEX_SE2 2527 36.644525 -16.160019 -1.912521 +VERTEX_SE2 2528 37.634960 -16.479865 -0.341191 +VERTEX_SE2 2529 38.587163 -16.834769 -0.349933 +VERTEX_SE2 2530 39.531773 -17.183472 -0.373434 +VERTEX_SE2 2531 40.410097 -17.552367 -0.377927 +VERTEX_SE2 2532 39.438707 -17.204423 2.753233 +VERTEX_SE2 2533 38.508055 -16.802300 2.751206 +VERTEX_SE2 2534 37.588900 -16.417157 2.743906 +VERTEX_SE2 2535 36.710183 -16.026972 2.744403 +VERTEX_SE2 2536 36.288092 -16.943527 -1.958907 +VERTEX_SE2 2537 35.897462 -17.875275 -1.958332 +VERTEX_SE2 2538 35.527682 -18.808908 -1.946348 +VERTEX_SE2 2539 35.144868 -19.740719 -1.937148 +VERTEX_SE2 2540 34.233463 -19.422893 2.788052 +VERTEX_SE2 2541 33.286658 -19.068779 2.807837 +VERTEX_SE2 2542 32.348573 -18.741935 2.858834 +VERTEX_SE2 2543 31.378849 -18.484220 2.889931 +VERTEX_SE2 2544 31.663901 -17.508724 1.355241 +VERTEX_SE2 2545 31.890244 -16.521970 1.375071 +VERTEX_SE2 2546 32.050250 -15.528591 1.375599 +VERTEX_SE2 2547 32.308617 -14.555525 1.351478 +VERTEX_SE2 2548 31.313955 -14.361496 2.937168 +VERTEX_SE2 2549 30.345570 -14.187422 2.875094 +VERTEX_SE2 2550 29.399091 -13.903958 2.848618 +VERTEX_SE2 2551 28.494004 -13.615229 2.836539 +VERTEX_SE2 2552 28.189399 -14.564063 -1.912261 +VERTEX_SE2 2553 27.792824 -15.512384 -1.906662 +VERTEX_SE2 2554 27.450946 -16.488845 -1.953694 +VERTEX_SE2 2555 27.078954 -17.409947 -1.965333 +VERTEX_SE2 2556 28.000297 -17.795435 -0.374963 +VERTEX_SE2 2557 28.922884 -18.181940 -0.403010 +VERTEX_SE2 2558 29.824937 -18.557876 -0.360607 +VERTEX_SE2 2559 30.763043 -18.911490 -0.355844 +VERTEX_SE2 2560 30.418011 -19.860468 -1.918134 +VERTEX_SE2 2561 30.085960 -20.867433 -1.957239 +VERTEX_SE2 2562 29.731382 -21.799482 -1.966375 +VERTEX_SE2 2563 29.338048 -22.701847 -1.926595 +VERTEX_SE2 2564 28.393999 -22.349810 2.811595 +VERTEX_SE2 2565 27.440323 -22.028396 2.776010 +VERTEX_SE2 2566 26.518721 -21.685369 2.785972 +VERTEX_SE2 2567 25.566980 -21.348872 2.769669 +VERTEX_SE2 2568 24.628405 -20.967137 2.748575 +VERTEX_SE2 2569 23.696976 -20.599843 2.719809 +VERTEX_SE2 2570 22.759023 -20.137765 2.758396 +VERTEX_SE2 2571 21.883098 -19.777143 2.803301 +VERTEX_SE2 2572 22.221937 -18.825234 1.202731 +VERTEX_SE2 2573 22.608668 -17.928001 1.202493 +VERTEX_SE2 2574 22.965699 -16.982177 1.226209 +VERTEX_SE2 2575 23.307984 -16.036438 1.215662 +VERTEX_SE2 2576 22.342066 -15.680530 2.776292 +VERTEX_SE2 2577 21.434139 -15.339892 2.788012 +VERTEX_SE2 2578 20.480881 -14.974007 2.777836 +VERTEX_SE2 2579 19.538579 -14.637976 2.780723 +VERTEX_SE2 2580 19.156264 -15.562425 -1.910717 +VERTEX_SE2 2581 18.825384 -16.481162 -1.872339 +VERTEX_SE2 2582 18.566780 -17.469922 -1.939095 +VERTEX_SE2 2583 18.198359 -18.371723 -1.950671 +VERTEX_SE2 2584 18.606414 -17.420274 1.169709 +VERTEX_SE2 2585 18.956332 -16.456631 1.143743 +VERTEX_SE2 2586 19.390113 -15.563705 1.151701 +VERTEX_SE2 2587 19.761952 -14.658507 1.132564 +VERTEX_SE2 2588 19.328401 -15.550570 -2.014786 +VERTEX_SE2 2589 18.897449 -16.434258 -1.995377 +VERTEX_SE2 2590 18.430522 -17.307929 -1.990177 +VERTEX_SE2 2591 18.061364 -18.225938 -1.953539 +VERTEX_SE2 2592 18.473207 -17.277050 1.215461 +VERTEX_SE2 2593 18.826516 -16.345425 1.218414 +VERTEX_SE2 2594 19.131402 -15.412733 1.207334 +VERTEX_SE2 2595 19.483246 -14.464609 1.218382 +VERTEX_SE2 2596 18.532602 -14.108951 2.785622 +VERTEX_SE2 2597 17.576084 -13.786951 2.778369 +VERTEX_SE2 2598 16.606891 -13.440104 2.817731 +VERTEX_SE2 2599 15.675442 -13.112116 2.822148 +VERTEX_SE2 2600 15.337510 -14.054823 -1.880092 +VERTEX_SE2 2601 15.012311 -15.013823 -1.864562 +VERTEX_SE2 2602 14.706806 -15.971362 -1.884416 +VERTEX_SE2 2603 14.390328 -16.920272 -1.879599 +VERTEX_SE2 2604 14.719296 -15.967756 1.260271 +VERTEX_SE2 2605 15.051854 -15.008588 1.242766 +VERTEX_SE2 2606 15.402758 -14.049312 1.224351 +VERTEX_SE2 2607 15.756675 -13.078741 1.237751 +VERTEX_SE2 2608 14.821684 -12.749244 2.830441 +VERTEX_SE2 2609 13.880420 -12.411914 2.776555 +VERTEX_SE2 2610 12.989204 -12.034444 2.789939 +VERTEX_SE2 2611 12.080220 -11.704618 2.778894 +VERTEX_SE2 2612 12.393290 -10.790950 1.208664 +VERTEX_SE2 2613 12.755394 -9.869925 1.202730 +VERTEX_SE2 2614 13.125349 -8.963264 1.244247 +VERTEX_SE2 2615 13.464235 -8.025940 1.249730 +VERTEX_SE2 2616 12.530947 -7.713716 2.815720 +VERTEX_SE2 2617 11.572124 -7.373334 2.833284 +VERTEX_SE2 2618 10.650803 -7.043072 2.835505 +VERTEX_SE2 2619 9.693193 -6.739452 2.796516 +VERTEX_SE2 2620 9.351698 -7.668388 -1.891794 +VERTEX_SE2 2621 9.044622 -8.598886 -1.856521 +VERTEX_SE2 2622 8.799590 -9.528766 -1.891068 +VERTEX_SE2 2623 8.513443 -10.429324 -1.881458 +VERTEX_SE2 2624 7.546546 -10.148198 2.857872 +VERTEX_SE2 2625 6.604490 -9.860061 2.862984 +VERTEX_SE2 2626 5.642499 -9.576210 2.849727 +VERTEX_SE2 2627 4.657834 -9.275770 2.862110 +VERTEX_SE2 2628 4.394386 -10.249342 -1.835540 +VERTEX_SE2 2629 4.132927 -11.246479 -1.814952 +VERTEX_SE2 2630 3.878959 -12.201733 -1.796866 +VERTEX_SE2 2631 3.615182 -13.154698 -1.806478 +VERTEX_SE2 2632 4.564073 -13.390706 -0.229278 +VERTEX_SE2 2633 5.513753 -13.627444 -0.238872 +VERTEX_SE2 2634 6.475394 -13.886582 -0.220281 +VERTEX_SE2 2635 7.465233 -14.128634 -0.233158 +VERTEX_SE2 2636 8.455043 -14.339898 -0.208533 +VERTEX_SE2 2637 9.423946 -14.560605 -0.178596 +VERTEX_SE2 2638 10.422572 -14.687305 -0.224678 +VERTEX_SE2 2639 11.384404 -14.884209 -0.230069 +VERTEX_SE2 2640 11.147851 -15.864361 -1.803259 +VERTEX_SE2 2641 10.928183 -16.830708 -1.800196 +VERTEX_SE2 2642 10.697300 -17.808553 -1.812387 +VERTEX_SE2 2643 10.507268 -18.775350 -1.770879 +VERTEX_SE2 2644 10.712361 -17.792974 1.368951 +VERTEX_SE2 2645 10.952954 -16.801284 1.357586 +VERTEX_SE2 2646 11.136029 -15.797156 1.377496 +VERTEX_SE2 2647 11.316315 -14.780973 1.387576 +VERTEX_SE2 2648 11.129176 -15.769116 -1.745384 +VERTEX_SE2 2649 10.939198 -16.761472 -1.772720 +VERTEX_SE2 2650 10.734515 -17.741575 -1.765327 +VERTEX_SE2 2651 10.521805 -18.742149 -1.737714 +VERTEX_SE2 2652 9.534713 -18.606439 2.985146 +VERTEX_SE2 2653 8.586003 -18.469890 3.000828 +VERTEX_SE2 2654 7.633553 -18.318283 2.993326 +VERTEX_SE2 2655 6.671168 -18.146014 2.995660 +VERTEX_SE2 2656 6.560471 -19.081434 -1.731670 +VERTEX_SE2 2657 6.378493 -20.087333 -1.731237 +VERTEX_SE2 2658 6.218086 -21.067129 -1.707667 +VERTEX_SE2 2659 6.092911 -22.025297 -1.722271 +VERTEX_SE2 2660 6.228040 -21.045552 1.383679 +VERTEX_SE2 2661 6.436609 -20.041515 1.376537 +VERTEX_SE2 2662 6.633968 -19.064206 1.393329 +VERTEX_SE2 2663 6.792898 -18.097508 1.413683 +VERTEX_SE2 2664 7.783627 -18.217980 -0.164157 +VERTEX_SE2 2665 8.798614 -18.388448 -0.192437 +VERTEX_SE2 2666 9.794473 -18.571208 -0.225618 +VERTEX_SE2 2667 10.787574 -18.787104 -0.207151 +VERTEX_SE2 2668 10.938587 -17.805811 1.358129 +VERTEX_SE2 2669 11.145779 -16.854824 1.377614 +VERTEX_SE2 2670 11.345796 -15.874213 1.355477 +VERTEX_SE2 2671 11.557186 -14.906197 1.380628 +VERTEX_SE2 2672 12.537307 -15.072658 -0.194822 +VERTEX_SE2 2673 13.518001 -15.266404 -0.188747 +VERTEX_SE2 2674 14.498005 -15.455016 -0.211887 +VERTEX_SE2 2675 15.459291 -15.669416 -0.184828 +VERTEX_SE2 2676 14.497254 -15.481188 2.966732 +VERTEX_SE2 2677 13.518233 -15.315131 2.987451 +VERTEX_SE2 2678 12.552635 -15.225721 2.986768 +VERTEX_SE2 2679 11.509751 -15.067166 3.023615 +VERTEX_SE2 2680 11.376285 -16.066383 -1.687895 +VERTEX_SE2 2681 11.269779 -17.077272 -1.661546 +VERTEX_SE2 2682 11.202411 -18.077774 -1.724756 +VERTEX_SE2 2683 11.045280 -19.072362 -1.716614 +VERTEX_SE2 2684 10.035872 -18.968964 2.988636 +VERTEX_SE2 2685 9.045882 -18.816771 3.018686 +VERTEX_SE2 2686 8.028916 -18.685316 3.016674 +VERTEX_SE2 2687 7.028663 -18.541160 3.023659 +VERTEX_SE2 2688 8.030187 -18.638157 -0.086761 +VERTEX_SE2 2689 9.022851 -18.723484 -0.064991 +VERTEX_SE2 2690 10.044374 -18.771116 -0.071471 +VERTEX_SE2 2691 11.051313 -18.878552 -0.078950 +VERTEX_SE2 2692 10.084200 -18.785763 3.081950 +VERTEX_SE2 2693 9.077507 -18.692542 3.036615 +VERTEX_SE2 2694 8.101754 -18.569952 3.002824 +VERTEX_SE2 2695 7.091945 -18.436512 3.015618 +VERTEX_SE2 2696 8.081795 -18.566638 -0.145492 +VERTEX_SE2 2697 9.097320 -18.700965 -0.134325 +VERTEX_SE2 2698 10.104948 -18.881211 -0.132462 +VERTEX_SE2 2699 11.065990 -18.967064 -0.191033 +VERTEX_SE2 2700 10.102603 -18.795512 2.936927 +VERTEX_SE2 2701 9.080626 -18.614284 2.963992 +VERTEX_SE2 2702 8.052967 -18.433289 2.951726 +VERTEX_SE2 2703 7.074902 -18.207722 2.973112 +VERTEX_SE2 2704 6.902952 -19.209088 -1.771488 +VERTEX_SE2 2705 6.718003 -20.158689 -1.767693 +VERTEX_SE2 2706 6.539490 -21.125413 -1.801226 +VERTEX_SE2 2707 6.338725 -22.100467 -1.781811 +VERTEX_SE2 2708 5.360669 -21.916949 2.936149 +VERTEX_SE2 2709 4.356453 -21.752725 2.937755 +VERTEX_SE2 2710 3.369327 -21.577007 2.917340 +VERTEX_SE2 2711 2.384525 -21.353076 2.930722 +VERTEX_SE2 2712 2.591205 -20.377800 1.391902 +VERTEX_SE2 2713 2.796963 -19.376941 1.414421 +VERTEX_SE2 2714 2.978182 -18.402364 1.388745 +VERTEX_SE2 2715 3.144911 -17.403259 1.401948 +VERTEX_SE2 2716 3.295892 -16.371813 1.423507 +VERTEX_SE2 2717 3.451424 -15.386387 1.454483 +VERTEX_SE2 2718 3.579161 -14.377525 1.441515 +VERTEX_SE2 2719 3.757103 -13.361506 1.438171 +VERTEX_SE2 2720 3.611700 -14.366696 -1.680569 +VERTEX_SE2 2721 3.486324 -15.347113 -1.677732 +VERTEX_SE2 2722 3.401272 -16.353695 -1.700577 +VERTEX_SE2 2723 3.280218 -17.383620 -1.709128 +VERTEX_SE2 2724 3.446753 -16.404660 1.454662 +VERTEX_SE2 2725 3.590617 -15.424161 1.513732 +VERTEX_SE2 2726 3.636296 -14.403194 1.488883 +VERTEX_SE2 2727 3.750507 -13.437522 1.487450 +VERTEX_SE2 2728 4.776982 -13.531560 -0.112070 +VERTEX_SE2 2729 5.762887 -13.655401 -0.094309 +VERTEX_SE2 2730 6.769574 -13.710787 -0.098441 +VERTEX_SE2 2731 7.805913 -13.823610 -0.114461 +VERTEX_SE2 2732 6.800838 -13.711265 3.031829 +VERTEX_SE2 2733 5.807939 -13.602702 3.076707 +VERTEX_SE2 2734 4.790526 -13.568180 3.100481 +VERTEX_SE2 2735 3.780058 -13.488481 3.105098 +VERTEX_SE2 2736 4.775796 -13.522891 -0.025442 +VERTEX_SE2 2737 5.797353 -13.546591 -0.024674 +VERTEX_SE2 2738 6.808284 -13.548481 0.002517 +VERTEX_SE2 2739 7.812802 -13.554360 -0.005950 +VERTEX_SE2 2740 6.844771 -13.586048 -3.107096 +VERTEX_SE2 2741 5.840062 -13.628651 -3.076990 +VERTEX_SE2 2742 4.818008 -13.727130 -3.091362 +VERTEX_SE2 2743 3.826194 -13.830653 -3.105619 +VERTEX_SE2 2744 4.829548 -13.799653 0.030596 +VERTEX_SE2 2745 5.833338 -13.769249 0.039525 +VERTEX_SE2 2746 6.790074 -13.728322 0.034393 +VERTEX_SE2 2747 7.803706 -13.726673 0.052087 +VERTEX_SE2 2748 7.883930 -14.686078 -1.521973 +VERTEX_SE2 2749 7.929929 -15.709994 -1.526144 +VERTEX_SE2 2750 7.971444 -16.707976 -1.514750 +VERTEX_SE2 2751 8.037138 -17.691822 -1.503336 +VERTEX_SE2 2752 7.944738 -16.684259 1.625134 +VERTEX_SE2 2753 7.913332 -15.679391 1.621956 +VERTEX_SE2 2754 7.875580 -14.664775 1.650569 +VERTEX_SE2 2755 7.819226 -13.647741 1.625349 +VERTEX_SE2 2756 7.906381 -14.647907 -1.465821 +VERTEX_SE2 2757 8.010968 -15.630267 -1.505822 +VERTEX_SE2 2758 8.089770 -16.618363 -1.492095 +VERTEX_SE2 2759 8.159002 -17.592479 -1.491080 +VERTEX_SE2 2760 8.134972 -16.613787 1.655360 +VERTEX_SE2 2761 8.054003 -15.614354 1.623649 +VERTEX_SE2 2762 7.981335 -14.619040 1.619531 +VERTEX_SE2 2763 7.945621 -13.631458 1.598222 +VERTEX_SE2 2764 8.965618 -13.613339 0.057962 +VERTEX_SE2 2765 10.001469 -13.560198 0.069321 +VERTEX_SE2 2766 11.003286 -13.463197 0.095778 +VERTEX_SE2 2767 12.021203 -13.392101 0.117462 +VERTEX_SE2 2768 11.018359 -13.534913 -3.001314 +VERTEX_SE2 2769 10.026581 -13.671979 -2.994646 +VERTEX_SE2 2770 9.045593 -13.827700 -2.962101 +VERTEX_SE2 2771 8.040828 -13.995443 -2.947390 +VERTEX_SE2 2772 9.052608 -13.794445 0.216035 +VERTEX_SE2 2773 10.038779 -13.560666 0.203703 +VERTEX_SE2 2774 11.035547 -13.392443 0.227656 +VERTEX_SE2 2775 12.001570 -13.170918 0.196459 +VERTEX_SE2 2776 12.185650 -14.154577 -1.332481 +VERTEX_SE2 2777 12.428542 -15.100556 -1.295420 +VERTEX_SE2 2778 12.681507 -16.065944 -1.268980 +VERTEX_SE2 2779 12.956957 -16.982619 -1.267767 +VERTEX_SE2 2780 12.010234 -17.301437 -2.809443 +VERTEX_SE2 2781 11.039643 -17.607924 -2.788419 +VERTEX_SE2 2782 10.122494 -17.931156 -2.785593 +VERTEX_SE2 2783 9.143931 -18.228877 -2.827540 +VERTEX_SE2 2784 8.858124 -17.292955 1.898945 +VERTEX_SE2 2785 8.560741 -16.315059 1.907300 +VERTEX_SE2 2786 8.233802 -15.334337 1.911867 +VERTEX_SE2 2787 7.899205 -14.352077 1.907020 +VERTEX_SE2 2788 8.856538 -14.039183 0.366630 +VERTEX_SE2 2789 9.831204 -13.656560 0.411819 +VERTEX_SE2 2790 10.773838 -13.268865 0.409143 +VERTEX_SE2 2791 11.728228 -12.877426 0.442280 +VERTEX_SE2 2792 10.838987 -13.284366 -2.676426 +VERTEX_SE2 2793 9.957463 -13.742674 -2.684631 +VERTEX_SE2 2794 9.069813 -14.176818 -2.678217 +VERTEX_SE2 2795 8.149573 -14.653675 -2.680715 +VERTEX_SE2 2796 7.699026 -13.770558 2.024681 +VERTEX_SE2 2797 7.266657 -12.843423 1.981580 +VERTEX_SE2 2798 6.872863 -11.918619 1.984986 +VERTEX_SE2 2799 6.491722 -10.964960 2.023302 +VERTEX_SE2 2800 7.438878 -10.529525 0.420512 +VERTEX_SE2 2801 8.357885 -10.115719 0.396789 +VERTEX_SE2 2802 9.291679 -9.771956 0.395213 +VERTEX_SE2 2803 10.205403 -9.381423 0.358338 +VERTEX_SE2 2804 9.277602 -9.767722 -2.801057 +VERTEX_SE2 2805 8.378201 -10.106516 -2.828396 +VERTEX_SE2 2806 7.454480 -10.443363 -2.842716 +VERTEX_SE2 2807 6.444500 -10.730832 -2.831324 +VERTEX_SE2 2808 6.766186 -11.710778 -1.239579 +VERTEX_SE2 2809 7.094482 -12.658330 -1.236429 +VERTEX_SE2 2810 7.427016 -13.604598 -1.217803 +VERTEX_SE2 2811 7.800578 -14.561708 -1.193916 +VERTEX_SE2 2812 6.873671 -14.911527 -2.766871 +VERTEX_SE2 2813 5.962076 -15.296826 -2.767625 +VERTEX_SE2 2814 4.989912 -15.628097 -2.771085 +VERTEX_SE2 2815 4.074578 -16.029796 -2.777078 +VERTEX_SE2 2816 3.695454 -15.069091 1.963747 +VERTEX_SE2 2817 3.330273 -14.145967 1.976020 +VERTEX_SE2 2818 2.938314 -13.258638 1.978104 +VERTEX_SE2 2819 2.569838 -12.337235 1.956880 +VERTEX_SE2 2820 1.671058 -12.682425 -2.784485 +VERTEX_SE2 2821 0.714134 -13.091409 -2.757469 +VERTEX_SE2 2822 -0.204333 -13.443928 -2.790071 +VERTEX_SE2 2823 -1.147897 -13.762289 -2.763220 +VERTEX_SE2 2824 -1.542247 -12.828721 1.988706 +VERTEX_SE2 2825 -1.928872 -11.920300 1.989157 +VERTEX_SE2 2826 -2.335783 -10.984222 2.015940 +VERTEX_SE2 2827 -2.733956 -10.096720 2.030469 +VERTEX_SE2 2828 -3.621292 -10.534870 -2.688997 +VERTEX_SE2 2829 -4.498716 -10.931682 -2.701939 +VERTEX_SE2 2830 -5.376553 -11.318598 -2.698171 +VERTEX_SE2 2831 -6.252396 -11.787702 -2.653839 +VERTEX_SE2 2832 -5.813658 -12.685778 -1.102443 +VERTEX_SE2 2833 -5.361565 -13.573092 -1.104451 +VERTEX_SE2 2834 -4.876747 -14.465085 -1.122297 +VERTEX_SE2 2835 -4.453475 -15.399703 -1.108157 +VERTEX_SE2 2836 -5.339466 -15.854672 -2.671762 +VERTEX_SE2 2837 -6.259104 -16.290356 -2.690331 +VERTEX_SE2 2838 -7.151182 -16.713735 -2.693494 +VERTEX_SE2 2839 -8.075150 -17.143100 -2.689599 +VERTEX_SE2 2840 -7.630434 -18.015596 -1.112824 +VERTEX_SE2 2841 -7.174012 -18.950667 -1.081287 +VERTEX_SE2 2842 -6.693855 -19.827990 -1.108555 +VERTEX_SE2 2843 -6.270189 -20.710187 -1.132446 +VERTEX_SE2 2844 -5.822177 -21.629133 -1.166544 +VERTEX_SE2 2845 -5.444090 -22.568354 -1.153441 +VERTEX_SE2 2846 -5.057190 -23.491287 -1.137840 +VERTEX_SE2 2847 -4.625170 -24.393410 -1.097457 +VERTEX_SE2 2848 -3.750440 -23.952378 0.475313 +VERTEX_SE2 2849 -2.891470 -23.497667 0.470293 +VERTEX_SE2 2850 -2.024474 -23.047829 0.439979 +VERTEX_SE2 2851 -1.101318 -22.614099 0.481337 +VERTEX_SE2 2852 -1.565786 -21.712871 2.022637 +VERTEX_SE2 2853 -2.024544 -20.802683 2.004247 +VERTEX_SE2 2854 -2.472780 -19.893593 1.988456 +VERTEX_SE2 2855 -2.865402 -19.018865 1.971913 +VERTEX_SE2 2856 -1.960364 -18.598221 0.401633 +VERTEX_SE2 2857 -1.058372 -18.183222 0.376214 +VERTEX_SE2 2858 -0.113637 -17.840306 0.384530 +VERTEX_SE2 2859 0.814397 -17.409285 0.359120 +VERTEX_SE2 2860 -0.151769 -17.757526 -2.779846 +VERTEX_SE2 2861 -1.076320 -18.129036 -2.780788 +VERTEX_SE2 2862 -2.006680 -18.484613 -2.812830 +VERTEX_SE2 2863 -2.991549 -18.796866 -2.829359 +VERTEX_SE2 2864 -2.030464 -18.505923 0.325056 +VERTEX_SE2 2865 -1.072453 -18.194622 0.343611 +VERTEX_SE2 2866 -0.130978 -17.873904 0.362426 +VERTEX_SE2 2867 0.812109 -17.540703 0.415005 +VERTEX_SE2 2868 1.234375 -18.460288 -1.139635 +VERTEX_SE2 2869 1.649208 -19.386945 -1.075550 +VERTEX_SE2 2870 2.092865 -20.286759 -1.088130 +VERTEX_SE2 2871 2.553002 -21.167701 -1.114959 +VERTEX_SE2 2872 1.654898 -21.590761 -2.685914 +VERTEX_SE2 2873 0.769397 -22.002429 -2.686083 +VERTEX_SE2 2874 -0.157835 -22.411462 -2.705473 +VERTEX_SE2 2875 -1.089396 -22.853421 -2.718360 +VERTEX_SE2 2876 -0.666613 -23.764080 -1.161525 +VERTEX_SE2 2877 -0.292550 -24.650176 -1.184505 +VERTEX_SE2 2878 0.064362 -25.615813 -1.156291 +VERTEX_SE2 2879 0.435582 -26.521260 -1.132669 +VERTEX_SE2 2880 -0.475730 -26.965846 -2.701825 +VERTEX_SE2 2881 -1.380451 -27.392110 -2.678870 +VERTEX_SE2 2882 -2.260921 -27.871560 -2.680443 +VERTEX_SE2 2883 -3.159532 -28.331351 -2.682863 +VERTEX_SE2 2884 -2.725848 -29.241474 -1.080838 +VERTEX_SE2 2885 -2.264900 -30.161823 -1.095598 +VERTEX_SE2 2886 -1.788101 -31.058074 -1.084857 +VERTEX_SE2 2887 -1.374794 -31.975724 -1.083081 +VERTEX_SE2 2888 -2.281588 -32.458350 -2.623976 +VERTEX_SE2 2889 -3.172182 -32.981566 -2.637734 +VERTEX_SE2 2890 -4.047133 -33.439566 -2.621048 +VERTEX_SE2 2891 -4.922321 -33.962075 -2.601159 +VERTEX_SE2 2892 -4.390294 -34.832746 -1.015794 +VERTEX_SE2 2893 -3.881827 -35.695926 -0.996554 +VERTEX_SE2 2894 -3.337838 -36.540104 -1.000761 +VERTEX_SE2 2895 -2.802294 -37.421710 -0.993359 +VERTEX_SE2 2896 -3.684895 -37.949079 -2.576035 +VERTEX_SE2 2897 -4.530821 -38.506890 -2.592503 +VERTEX_SE2 2898 -5.392579 -39.013365 -2.585289 +VERTEX_SE2 2899 -6.225311 -39.572465 -2.571135 +VERTEX_SE2 2900 -5.384397 -39.033099 0.631360 +VERTEX_SE2 2901 -4.575850 -38.437446 0.602188 +VERTEX_SE2 2902 -3.741535 -37.867820 0.606234 +VERTEX_SE2 2903 -2.904781 -37.293391 0.593745 +VERTEX_SE2 2904 -3.725998 -37.856931 -2.549340 +VERTEX_SE2 2905 -4.591473 -38.415854 -2.514471 +VERTEX_SE2 2906 -5.420209 -39.058892 -2.481905 +VERTEX_SE2 2907 -6.234069 -39.660523 -2.497753 +VERTEX_SE2 2908 -5.438019 -39.072351 0.618972 +VERTEX_SE2 2909 -4.616931 -38.472842 0.603006 +VERTEX_SE2 2910 -3.788975 -37.915332 0.613668 +VERTEX_SE2 2911 -2.967582 -37.324734 0.600817 +VERTEX_SE2 2912 -3.527836 -36.482546 2.195687 +VERTEX_SE2 2913 -4.146530 -35.667310 2.222061 +VERTEX_SE2 2914 -4.752745 -34.840726 2.179983 +VERTEX_SE2 2915 -5.264740 -33.983493 2.219805 +VERTEX_SE2 2916 -4.677584 -34.785296 -0.959125 +VERTEX_SE2 2917 -4.054143 -35.575459 -0.988335 +VERTEX_SE2 2918 -3.466180 -36.419852 -0.993054 +VERTEX_SE2 2919 -2.893161 -37.286555 -1.020998 +VERTEX_SE2 2920 -3.729890 -37.804344 -2.607233 +VERTEX_SE2 2921 -4.597031 -38.326076 -2.605341 +VERTEX_SE2 2922 -5.434152 -38.834519 -2.562776 +VERTEX_SE2 2923 -6.251302 -39.360796 -2.581420 +VERTEX_SE2 2924 -6.801113 -38.508236 2.139305 +VERTEX_SE2 2925 -7.290420 -37.680516 2.178769 +VERTEX_SE2 2926 -7.864782 -36.877501 2.185039 +VERTEX_SE2 2927 -8.443482 -36.074141 2.155900 +VERTEX_SE2 2928 -7.599397 -35.530955 0.532210 +VERTEX_SE2 2929 -6.747129 -35.043823 0.537340 +VERTEX_SE2 2930 -5.881441 -34.500930 0.553245 +VERTEX_SE2 2931 -5.047581 -33.957969 0.553199 +VERTEX_SE2 2932 -5.880171 -34.478703 -2.552277 +VERTEX_SE2 2933 -6.699460 -35.096286 -2.543707 +VERTEX_SE2 2934 -7.479253 -35.666393 -2.590123 +VERTEX_SE2 2935 -8.354558 -36.186002 -2.592833 +VERTEX_SE2 2936 -7.488887 -35.646224 0.511052 +VERTEX_SE2 2937 -6.625831 -35.138621 0.511547 +VERTEX_SE2 2938 -5.782499 -34.657928 0.503868 +VERTEX_SE2 2939 -4.905081 -34.129971 0.528030 +VERTEX_SE2 2940 -5.797766 -34.614075 -2.617466 +VERTEX_SE2 2941 -6.691618 -35.087937 -2.623169 +VERTEX_SE2 2942 -7.566388 -35.591667 -2.609702 +VERTEX_SE2 2943 -8.418232 -36.078880 -2.638636 +VERTEX_SE2 2944 -8.902047 -35.191712 2.064819 +VERTEX_SE2 2945 -9.397782 -34.309854 2.026696 +VERTEX_SE2 2946 -9.854634 -33.398290 2.067176 +VERTEX_SE2 2947 -10.336102 -32.556631 2.094582 +VERTEX_SE2 2948 -11.187098 -33.057427 -2.582283 +VERTEX_SE2 2949 -12.021560 -33.543587 -2.622895 +VERTEX_SE2 2950 -12.890084 -34.030620 -2.631635 +VERTEX_SE2 2951 -13.758030 -34.522678 -2.597033 +VERTEX_SE2 2952 -13.215545 -35.355734 -1.003018 +VERTEX_SE2 2953 -12.668119 -36.182529 -1.010612 +VERTEX_SE2 2954 -12.168233 -37.069389 -0.982136 +VERTEX_SE2 2955 -11.601959 -37.882053 -0.959403 +VERTEX_SE2 2956 -12.166427 -37.072445 2.162047 +VERTEX_SE2 2957 -12.714276 -36.253271 2.130027 +VERTEX_SE2 2958 -13.262822 -35.389417 2.118401 +VERTEX_SE2 2959 -13.803984 -34.517035 2.118872 +VERTEX_SE2 2960 -13.311403 -35.368191 -1.048178 +VERTEX_SE2 2961 -12.859927 -36.222686 -1.077511 +VERTEX_SE2 2962 -12.404493 -37.085300 -1.062414 +VERTEX_SE2 2963 -11.901283 -37.957122 -1.059768 +VERTEX_SE2 2964 -12.795814 -38.463165 -2.585343 +VERTEX_SE2 2965 -13.653600 -38.982748 -2.563538 +VERTEX_SE2 2966 -14.455242 -39.545736 -2.605429 +VERTEX_SE2 2967 -15.328435 -40.047258 -2.599906 +VERTEX_SE2 2968 -15.843338 -39.245376 2.135829 +VERTEX_SE2 2969 -16.357517 -38.364495 2.205829 +VERTEX_SE2 2970 -16.977189 -37.583916 2.187836 +VERTEX_SE2 2971 -17.556764 -36.753105 2.213381 +VERTEX_SE2 2972 -16.958966 -37.548651 -0.927199 +VERTEX_SE2 2973 -16.344325 -38.343319 -0.917878 +VERTEX_SE2 2974 -15.707069 -39.143660 -0.931705 +VERTEX_SE2 2975 -15.137356 -39.934662 -0.894348 +VERTEX_SE2 2976 -15.916593 -40.553779 -2.474353 +VERTEX_SE2 2977 -16.688183 -41.137646 -2.485813 +VERTEX_SE2 2978 -17.469945 -41.760196 -2.527490 +VERTEX_SE2 2979 -18.295813 -42.342409 -2.532141 +VERTEX_SE2 2980 -17.459436 -41.755211 0.569724 +VERTEX_SE2 2981 -16.606579 -41.225434 0.555265 +VERTEX_SE2 2982 -15.718539 -40.703497 0.595069 +VERTEX_SE2 2983 -14.886468 -40.170816 0.579070 +VERTEX_SE2 2984 -15.720881 -40.690842 -2.551696 +VERTEX_SE2 2985 -16.528960 -41.241122 -2.562979 +VERTEX_SE2 2986 -17.380327 -41.793302 -2.539038 +VERTEX_SE2 2987 -18.236483 -42.400240 -2.524011 +VERTEX_SE2 2988 -18.841502 -41.581449 2.197704 +VERTEX_SE2 2989 -19.395319 -40.819778 2.194470 +VERTEX_SE2 2990 -19.949081 -40.025872 2.240996 +VERTEX_SE2 2991 -20.557813 -39.263935 2.270314 +VERTEX_SE2 2992 -21.314298 -39.899229 -2.462421 +VERTEX_SE2 2993 -22.108213 -40.547627 -2.474768 +VERTEX_SE2 2994 -22.878022 -41.142351 -2.467351 +VERTEX_SE2 2995 -23.627674 -41.783358 -2.441699 +VERTEX_SE2 2996 -22.938959 -42.577770 -0.863094 +VERTEX_SE2 2997 -22.309448 -43.372196 -0.873614 +VERTEX_SE2 2998 -21.652519 -44.104531 -0.881228 +VERTEX_SE2 2999 -20.967742 -44.849348 -0.904868 +VERTEX_SE2 3000 -21.778824 -45.501642 -2.452303 +VERTEX_SE2 3001 -22.518111 -46.097332 -2.508022 +VERTEX_SE2 3002 -23.342176 -46.693827 -2.519087 +VERTEX_SE2 3003 -24.159428 -47.294262 -2.522294 +VERTEX_SE2 3004 -24.793034 -46.485413 2.160621 +VERTEX_SE2 3005 -25.339203 -45.624114 2.165829 +VERTEX_SE2 3006 -25.879545 -44.807289 2.190600 +VERTEX_SE2 3007 -26.458990 -43.995897 2.172186 +VERTEX_SE2 3008 -25.907247 -44.822915 -0.938384 +VERTEX_SE2 3009 -25.317898 -45.584625 -0.943758 +VERTEX_SE2 3010 -24.692490 -46.411308 -0.942726 +VERTEX_SE2 3011 -24.132324 -47.256101 -0.964685 +VERTEX_SE2 3012 -24.708347 -46.407044 2.168535 +VERTEX_SE2 3013 -25.241426 -45.542506 2.173274 +VERTEX_SE2 3014 -25.805032 -44.700737 2.147222 +VERTEX_SE2 3015 -26.374828 -43.888522 2.162804 +VERTEX_SE2 3016 -25.563792 -43.289477 0.603114 +VERTEX_SE2 3017 -24.762750 -42.744462 0.616405 +VERTEX_SE2 3018 -23.967888 -42.172140 0.630896 +VERTEX_SE2 3019 -23.169146 -41.582739 0.577961 +VERTEX_SE2 3020 -23.981726 -42.101716 -2.575294 +VERTEX_SE2 3021 -24.868086 -42.629398 -2.586632 +VERTEX_SE2 3022 -25.699738 -43.159261 -2.580904 +VERTEX_SE2 3023 -26.529086 -43.672576 -2.601052 +VERTEX_SE2 3024 -27.014289 -42.846232 2.114114 +VERTEX_SE2 3025 -27.541038 -42.019491 2.116108 +VERTEX_SE2 3026 -28.061583 -41.182411 2.117961 +VERTEX_SE2 3027 -28.600514 -40.347161 2.168753 +VERTEX_SE2 3028 -28.040592 -41.158175 -0.987357 +VERTEX_SE2 3029 -27.493352 -41.959245 -0.969919 +VERTEX_SE2 3030 -26.878341 -42.756252 -0.965536 +VERTEX_SE2 3031 -26.320813 -43.557282 -0.975295 +VERTEX_SE2 3032 -26.896354 -42.739437 2.176275 +VERTEX_SE2 3033 -27.458478 -41.915047 2.157390 +VERTEX_SE2 3034 -28.068940 -41.076290 2.142206 +VERTEX_SE2 3035 -28.615516 -40.228878 2.137978 +VERTEX_SE2 3036 -29.432456 -40.752961 -2.531078 +VERTEX_SE2 3037 -30.227821 -41.313419 -2.554670 +VERTEX_SE2 3038 -31.094032 -41.855454 -2.596888 +VERTEX_SE2 3039 -31.928180 -42.386072 -2.612597 +VERTEX_SE2 3040 -32.413846 -41.552285 2.070739 +VERTEX_SE2 3041 -32.886519 -40.662206 2.076022 +VERTEX_SE2 3042 -33.383708 -39.789234 2.092912 +VERTEX_SE2 3043 -33.932808 -38.958049 2.115913 +VERTEX_SE2 3044 -33.425307 -39.797783 -0.998667 +VERTEX_SE2 3045 -32.881607 -40.632106 -1.007831 +VERTEX_SE2 3046 -32.393524 -41.503778 -1.023330 +VERTEX_SE2 3047 -31.853445 -42.353117 -1.050996 +VERTEX_SE2 3048 -30.963378 -41.857343 0.507934 +VERTEX_SE2 3049 -30.109316 -41.357037 0.532380 +VERTEX_SE2 3050 -29.290256 -40.835972 0.534228 +VERTEX_SE2 3051 -28.437462 -40.339678 0.548325 +VERTEX_SE2 3052 -27.580186 -39.828106 0.558035 +VERTEX_SE2 3053 -26.732284 -39.296913 0.515141 +VERTEX_SE2 3054 -25.905138 -38.788199 0.518368 +VERTEX_SE2 3055 -25.046921 -38.301777 0.529622 +VERTEX_SE2 3056 -24.555254 -39.162891 -1.059898 +VERTEX_SE2 3057 -24.066513 -40.026894 -1.089894 +VERTEX_SE2 3058 -23.628034 -40.918945 -1.056632 +VERTEX_SE2 3059 -23.119702 -41.774258 -1.047663 +VERTEX_SE2 3060 -24.011449 -42.313185 -2.611099 +VERTEX_SE2 3061 -24.865093 -42.836000 -2.620697 +VERTEX_SE2 3062 -25.740836 -43.337839 -2.600551 +VERTEX_SE2 3063 -26.605788 -43.877395 -2.578475 +VERTEX_SE2 3064 -26.073353 -44.682284 -0.989610 +VERTEX_SE2 3065 -25.462070 -45.533858 -0.973585 +VERTEX_SE2 3066 -24.914636 -46.377927 -0.987437 +VERTEX_SE2 3067 -24.393877 -47.215731 -0.939542 +VERTEX_SE2 3068 -25.191364 -47.789758 -2.503877 +VERTEX_SE2 3069 -26.020591 -48.377235 -2.543969 +VERTEX_SE2 3070 -26.837005 -48.925173 -2.549638 +VERTEX_SE2 3071 -27.674965 -49.451441 -2.570282 +VERTEX_SE2 3072 -27.110028 -50.248922 -0.979737 +VERTEX_SE2 3073 -26.563325 -51.061301 -0.974670 +VERTEX_SE2 3074 -26.009897 -51.912985 -0.989995 +VERTEX_SE2 3075 -25.473660 -52.700096 -0.992406 +VERTEX_SE2 3076 -24.590960 -52.154643 0.643544 +VERTEX_SE2 3077 -23.799664 -51.561658 0.655524 +VERTEX_SE2 3078 -22.984922 -50.952133 0.664684 +VERTEX_SE2 3079 -22.192070 -50.324214 0.646313 +VERTEX_SE2 3080 -22.786413 -49.520610 2.263663 +VERTEX_SE2 3081 -23.413981 -48.771792 2.226367 +VERTEX_SE2 3082 -24.064034 -47.985038 2.230531 +VERTEX_SE2 3083 -24.676633 -47.208399 2.249739 +VERTEX_SE2 3084 -25.445520 -47.850759 -2.473286 +VERTEX_SE2 3085 -26.211694 -48.461239 -2.451413 +VERTEX_SE2 3086 -27.019019 -49.049359 -2.448883 +VERTEX_SE2 3087 -27.792318 -49.686919 -2.419541 +VERTEX_SE2 3088 -28.473465 -48.949813 2.322134 +VERTEX_SE2 3089 -29.108662 -48.256034 2.295238 +VERTEX_SE2 3090 -29.742348 -47.515302 2.253094 +VERTEX_SE2 3091 -30.347875 -46.714352 2.266358 +VERTEX_SE2 3092 -29.590067 -46.089430 0.700108 +VERTEX_SE2 3093 -28.815815 -45.452983 0.712760 +VERTEX_SE2 3094 -28.032352 -44.801511 0.708597 +VERTEX_SE2 3095 -27.295946 -44.183126 0.697215 +VERTEX_SE2 3096 -28.053087 -44.826673 -2.439940 +VERTEX_SE2 3097 -28.850627 -45.469787 -2.435390 +VERTEX_SE2 3098 -29.638531 -46.113007 -2.423432 +VERTEX_SE2 3099 -30.410919 -46.794600 -2.407492 +VERTEX_SE2 3100 -31.064678 -46.080358 2.284524 +VERTEX_SE2 3101 -31.738925 -45.344549 2.291718 +VERTEX_SE2 3102 -32.430151 -44.608687 2.312043 +VERTEX_SE2 3103 -33.085161 -43.857247 2.317813 +VERTEX_SE2 3104 -32.409998 -44.560528 -0.831997 +VERTEX_SE2 3105 -31.766732 -45.309622 -0.814505 +VERTEX_SE2 3106 -31.100350 -46.049097 -0.796716 +VERTEX_SE2 3107 -30.435363 -46.773123 -0.804955 +VERTEX_SE2 3108 -31.145165 -46.031578 2.330655 +VERTEX_SE2 3109 -31.848761 -45.316989 2.338612 +VERTEX_SE2 3110 -32.559948 -44.590811 2.360282 +VERTEX_SE2 3111 -33.266575 -43.892514 2.341844 +VERTEX_SE2 3112 -33.953923 -43.163108 2.343288 +VERTEX_SE2 3113 -34.701704 -42.477552 2.334789 +VERTEX_SE2 3114 -35.366350 -41.788395 2.372849 +VERTEX_SE2 3115 -36.083180 -41.119651 2.364043 +VERTEX_SE2 3116 -35.377122 -40.427813 0.822193 +VERTEX_SE2 3117 -34.683034 -39.676021 0.788994 +VERTEX_SE2 3118 -33.949384 -38.998450 0.746076 +VERTEX_SE2 3119 -33.180809 -38.302167 0.791579 +VERTEX_SE2 3120 -33.883797 -37.548116 2.359399 +VERTEX_SE2 3121 -34.566026 -36.852860 2.356678 +VERTEX_SE2 3122 -35.310420 -36.134404 2.370467 +VERTEX_SE2 3123 -36.016215 -35.465085 2.345680 +VERTEX_SE2 3124 -35.261147 -34.779294 0.757170 +VERTEX_SE2 3125 -34.534049 -34.070806 0.728022 +VERTEX_SE2 3126 -33.798057 -33.408279 0.704150 +VERTEX_SE2 3127 -33.058530 -32.762768 0.698521 +VERTEX_SE2 3128 -32.314395 -32.140327 0.679892 +VERTEX_SE2 3129 -31.515114 -31.507003 0.654148 +VERTEX_SE2 3130 -30.775466 -30.923823 0.622499 +VERTEX_SE2 3131 -29.942310 -30.368545 0.626379 +VERTEX_SE2 3132 -29.323080 -31.166328 -0.929091 +VERTEX_SE2 3133 -28.715829 -31.981722 -0.931822 +VERTEX_SE2 3134 -28.131942 -32.829173 -0.944781 +VERTEX_SE2 3135 -27.503304 -33.650969 -0.964417 +VERTEX_SE2 3136 -28.368399 -34.230789 -2.551312 +VERTEX_SE2 3137 -29.197718 -34.802757 -2.590587 +VERTEX_SE2 3138 -30.056153 -35.335195 -2.589005 +VERTEX_SE2 3139 -30.903332 -35.850548 -2.612178 +VERTEX_SE2 3140 -31.385973 -34.970163 2.070067 +VERTEX_SE2 3141 -31.891807 -34.049358 2.066412 +VERTEX_SE2 3142 -32.384630 -33.188916 2.062879 +VERTEX_SE2 3143 -32.809122 -32.303222 2.053648 +VERTEX_SE2 3144 -32.341345 -33.166729 -1.084042 +VERTEX_SE2 3145 -31.884593 -34.058730 -1.078209 +VERTEX_SE2 3146 -31.420532 -34.976845 -1.064145 +VERTEX_SE2 3147 -30.930210 -35.843110 -1.083184 +VERTEX_SE2 3148 -30.478985 -36.730742 -1.071900 +VERTEX_SE2 3149 -29.962136 -37.650694 -1.055543 +VERTEX_SE2 3150 -29.414280 -38.516321 -1.071590 +VERTEX_SE2 3151 -28.929570 -39.385007 -1.052321 +VERTEX_SE2 3152 -29.793274 -39.873243 -2.604226 +VERTEX_SE2 3153 -30.638697 -40.368072 -2.619340 +VERTEX_SE2 3154 -31.502741 -40.874843 -2.613808 +VERTEX_SE2 3155 -32.393098 -41.388680 -2.624592 +VERTEX_SE2 3156 -32.881094 -40.493096 2.104403 +VERTEX_SE2 3157 -33.427743 -39.630553 2.089337 +VERTEX_SE2 3158 -33.920377 -38.756867 2.078558 +VERTEX_SE2 3159 -34.427826 -37.911230 2.102856 +VERTEX_SE2 3160 -35.291096 -38.460748 -2.628659 +VERTEX_SE2 3161 -36.196279 -38.959339 -2.609608 +VERTEX_SE2 3162 -37.078004 -39.474529 -2.574139 +VERTEX_SE2 3163 -37.926552 -40.006529 -2.601893 +VERTEX_SE2 3164 -37.449192 -40.863360 -1.066198 +VERTEX_SE2 3165 -36.967513 -41.745171 -1.082187 +VERTEX_SE2 3166 -36.486615 -42.577727 -1.096004 +VERTEX_SE2 3167 -36.066094 -43.510804 -1.089070 +VERTEX_SE2 3168 -35.189848 -43.088562 0.499740 +VERTEX_SE2 3169 -34.342378 -42.602331 0.504273 +VERTEX_SE2 3170 -33.454372 -42.124968 0.519880 +VERTEX_SE2 3171 -32.593112 -41.615644 0.548645 +VERTEX_SE2 3172 -33.471070 -42.113462 -2.574521 +VERTEX_SE2 3173 -34.321859 -42.636494 -2.560208 +VERTEX_SE2 3174 -35.158735 -43.204486 -2.562434 +VERTEX_SE2 3175 -36.043347 -43.753447 -2.578743 +VERTEX_SE2 3176 -35.190898 -43.196283 0.526572 +VERTEX_SE2 3177 -34.304262 -42.682364 0.499002 +VERTEX_SE2 3178 -33.403839 -42.221545 0.485915 +VERTEX_SE2 3179 -32.519722 -41.739483 0.484357 +VERTEX_SE2 3180 -33.376216 -42.247398 -2.692938 +VERTEX_SE2 3181 -34.275021 -42.615264 -2.716927 +VERTEX_SE2 3182 -35.177622 -43.041119 -2.736319 +VERTEX_SE2 3183 -36.101172 -43.423397 -2.797146 +VERTEX_SE2 3184 -35.098741 -43.084226 0.385350 +VERTEX_SE2 3185 -34.162657 -42.695030 0.372821 +VERTEX_SE2 3186 -33.224135 -42.312207 0.362218 +VERTEX_SE2 3187 -32.271812 -41.942911 0.357879 +VERTEX_SE2 3188 -31.900146 -42.877323 -1.218841 +VERTEX_SE2 3189 -31.578763 -43.812146 -1.218770 +VERTEX_SE2 3190 -31.266101 -44.774975 -1.239342 +VERTEX_SE2 3191 -30.935567 -45.687321 -1.248634 +VERTEX_SE2 3192 -31.869844 -46.003210 -2.799229 +VERTEX_SE2 3193 -32.812534 -46.320487 -2.814433 +VERTEX_SE2 3194 -33.727882 -46.629226 -2.807576 +VERTEX_SE2 3195 -34.705430 -46.979055 -2.807006 +VERTEX_SE2 3196 -35.019195 -46.030791 1.889170 +VERTEX_SE2 3197 -35.341813 -45.095255 1.886631 +VERTEX_SE2 3198 -35.680212 -44.149411 1.874113 +VERTEX_SE2 3199 -35.987751 -43.164939 1.908195 +VERTEX_SE2 3200 -35.684536 -44.108923 -1.212125 +VERTEX_SE2 3201 -35.338505 -45.050141 -1.205750 +VERTEX_SE2 3202 -34.968253 -46.003782 -1.224951 +VERTEX_SE2 3203 -34.634198 -46.924254 -1.202232 +VERTEX_SE2 3204 -33.682851 -46.579185 0.392448 +VERTEX_SE2 3205 -32.780448 -46.201379 0.406077 +VERTEX_SE2 3206 -31.853074 -45.815812 0.394150 +VERTEX_SE2 3207 -30.910500 -45.444952 0.395613 +VERTEX_SE2 3208 -31.300569 -44.529373 1.944623 +VERTEX_SE2 3209 -31.643675 -43.592958 1.947745 +VERTEX_SE2 3210 -32.009977 -42.656932 1.953894 +VERTEX_SE2 3211 -32.382485 -41.717603 1.977887 +VERTEX_SE2 3212 -31.480550 -41.299612 0.399557 +VERTEX_SE2 3213 -30.590542 -40.872619 0.358369 +VERTEX_SE2 3214 -29.611644 -40.531514 0.386017 +VERTEX_SE2 3215 -28.704562 -40.154200 0.420477 +VERTEX_SE2 3216 -29.177122 -39.223683 2.013357 +VERTEX_SE2 3217 -29.611642 -38.343800 2.029010 +VERTEX_SE2 3218 -30.036429 -37.443563 1.997650 +VERTEX_SE2 3219 -30.440791 -36.543862 1.972879 +VERTEX_SE2 3220 -29.551188 -36.159313 0.386269 +VERTEX_SE2 3221 -28.623628 -35.795192 0.382590 +VERTEX_SE2 3222 -27.716884 -35.420603 0.353539 +VERTEX_SE2 3223 -26.766528 -35.053175 0.370750 +VERTEX_SE2 3224 -27.725193 -35.399562 -2.777666 +VERTEX_SE2 3225 -28.682984 -35.758515 -2.786018 +VERTEX_SE2 3226 -29.617871 -36.083627 -2.790647 +VERTEX_SE2 3227 -30.537351 -36.428450 -2.816408 +VERTEX_SE2 3228 -30.211814 -37.426217 -1.261713 +VERTEX_SE2 3229 -29.915792 -38.384849 -1.265794 +VERTEX_SE2 3230 -29.621997 -39.350722 -1.277798 +VERTEX_SE2 3231 -29.341711 -40.308595 -1.278177 +VERTEX_SE2 3232 -30.251334 -40.581388 -2.849712 +VERTEX_SE2 3233 -31.211476 -40.885910 -2.803435 +VERTEX_SE2 3234 -32.162875 -41.193880 -2.789643 +VERTEX_SE2 3235 -33.127478 -41.551509 -2.771075 +VERTEX_SE2 3236 -32.772966 -42.490383 -1.195169 +VERTEX_SE2 3237 -32.425272 -43.422749 -1.177581 +VERTEX_SE2 3238 -32.045522 -44.315662 -1.141910 +VERTEX_SE2 3239 -31.631387 -45.242077 -1.096798 +VERTEX_SE2 3240 -30.731040 -44.804247 0.452262 +VERTEX_SE2 3241 -29.839294 -44.364366 0.463693 +VERTEX_SE2 3242 -28.924394 -43.911387 0.407651 +VERTEX_SE2 3243 -27.999235 -43.503083 0.421780 +VERTEX_SE2 3244 -27.625935 -44.404810 -1.128130 +VERTEX_SE2 3245 -27.182755 -45.331261 -1.128543 +VERTEX_SE2 3246 -26.778769 -46.230565 -1.139825 +VERTEX_SE2 3247 -26.406777 -47.162819 -1.141303 +VERTEX_SE2 3248 -27.316239 -47.564254 -2.746538 +VERTEX_SE2 3249 -28.241916 -47.922625 -2.778716 +VERTEX_SE2 3250 -29.190345 -48.258976 -2.789137 +VERTEX_SE2 3251 -30.153460 -48.605150 -2.769119 +VERTEX_SE2 3252 -29.800770 -49.582442 -1.198174 +VERTEX_SE2 3253 -29.397486 -50.481883 -1.196022 +VERTEX_SE2 3254 -28.977428 -51.422848 -1.188130 +VERTEX_SE2 3255 -28.547849 -52.395860 -1.221583 +VERTEX_SE2 3256 -27.604626 -52.048425 0.317967 +VERTEX_SE2 3257 -26.666330 -51.719740 0.336946 +VERTEX_SE2 3258 -25.762180 -51.370769 0.372806 +VERTEX_SE2 3259 -24.826756 -51.011790 0.361048 +VERTEX_SE2 3260 -25.174906 -50.073277 1.953238 +VERTEX_SE2 3261 -25.549097 -49.177848 1.988600 +VERTEX_SE2 3262 -25.943824 -48.216803 1.994353 +VERTEX_SE2 3263 -26.309048 -47.324396 2.004299 +VERTEX_SE2 3264 -25.902607 -48.241039 -1.177391 +VERTEX_SE2 3265 -25.542352 -49.159478 -1.153373 +VERTEX_SE2 3266 -25.129456 -50.079252 -1.132460 +VERTEX_SE2 3267 -24.707239 -50.999279 -1.162416 +VERTEX_SE2 3268 -23.779315 -50.649109 0.407744 +VERTEX_SE2 3269 -22.860009 -50.256654 0.375794 +VERTEX_SE2 3270 -21.945912 -49.885557 0.364636 +VERTEX_SE2 3271 -21.014754 -49.534907 0.397919 +VERTEX_SE2 3272 -21.390912 -48.644428 1.970379 +VERTEX_SE2 3273 -21.762303 -47.721062 1.990020 +VERTEX_SE2 3274 -22.192202 -46.829660 1.972062 +VERTEX_SE2 3275 -22.589892 -45.907318 1.946975 +VERTEX_SE2 3276 -22.956209 -45.004090 1.899835 +VERTEX_SE2 3277 -23.284480 -44.063550 1.889595 +VERTEX_SE2 3278 -23.576640 -43.102980 1.935309 +VERTEX_SE2 3279 -23.988735 -42.139774 1.919129 +VERTEX_SE2 3280 -23.668788 -43.053588 -1.232371 +VERTEX_SE2 3281 -23.354359 -43.986603 -1.225996 +VERTEX_SE2 3282 -23.008306 -44.960590 -1.227585 +VERTEX_SE2 3283 -22.674036 -45.905768 -1.258188 +VERTEX_SE2 3284 -23.614615 -46.232120 -2.843363 +VERTEX_SE2 3285 -24.576203 -46.518574 -2.807033 +VERTEX_SE2 3286 -25.543266 -46.795095 -2.817404 +VERTEX_SE2 3287 -26.490798 -47.145238 -2.820957 +VERTEX_SE2 3288 -27.488436 -47.420191 -2.836633 +VERTEX_SE2 3289 -28.444312 -47.713931 -2.814262 +VERTEX_SE2 3290 -29.399844 -48.036910 -2.855508 +VERTEX_SE2 3291 -30.357371 -48.372741 -2.806759 +VERTEX_SE2 3292 -30.661083 -47.431204 1.921276 +VERTEX_SE2 3293 -31.008501 -46.482102 1.902152 +VERTEX_SE2 3294 -31.325359 -45.535204 1.924091 +VERTEX_SE2 3295 -31.686074 -44.611208 1.950712 +VERTEX_SE2 3296 -32.615806 -44.978681 -2.769713 +VERTEX_SE2 3297 -33.558929 -45.323714 -2.762899 +VERTEX_SE2 3298 -34.524784 -45.705359 -2.777630 +VERTEX_SE2 3299 -35.447227 -46.016308 -2.771941 +VERTEX_SE2 3300 -34.515729 -45.669001 0.360365 +VERTEX_SE2 3301 -33.598531 -45.315333 0.340821 +VERTEX_SE2 3302 -32.641214 -45.027997 0.369413 +VERTEX_SE2 3303 -31.704336 -44.638088 0.398695 +VERTEX_SE2 3304 -31.333098 -45.571290 -1.189135 +VERTEX_SE2 3305 -30.999640 -46.456806 -1.218521 +VERTEX_SE2 3306 -30.662504 -47.417712 -1.229584 +VERTEX_SE2 3307 -30.306387 -48.359435 -1.224347 +VERTEX_SE2 3308 -31.249905 -48.673632 -2.804662 +VERTEX_SE2 3309 -32.193345 -49.003112 -2.806107 +VERTEX_SE2 3310 -33.127363 -49.374658 -2.815449 +VERTEX_SE2 3311 -34.091347 -49.686814 -2.798380 +VERTEX_SE2 3312 -33.752288 -50.625092 -1.216015 +VERTEX_SE2 3313 -33.418254 -51.575333 -1.190949 +VERTEX_SE2 3314 -33.007493 -52.502800 -1.227774 +VERTEX_SE2 3315 -32.703609 -53.411528 -1.205018 +VERTEX_SE2 3316 -33.081062 -52.481842 1.940112 +VERTEX_SE2 3317 -33.417491 -51.549290 1.930644 +VERTEX_SE2 3318 -33.746064 -50.621698 1.923978 +VERTEX_SE2 3319 -34.097658 -49.708407 1.943563 +VERTEX_SE2 3320 -33.735010 -50.602501 -1.207547 +VERTEX_SE2 3321 -33.405505 -51.557392 -1.223243 +VERTEX_SE2 3322 -33.075079 -52.507987 -1.200605 +VERTEX_SE2 3323 -32.690366 -53.436767 -1.205388 +VERTEX_SE2 3324 -32.329303 -54.342066 -1.202745 +VERTEX_SE2 3325 -31.990317 -55.281551 -1.180042 +VERTEX_SE2 3326 -31.629533 -56.226945 -1.201974 +VERTEX_SE2 3327 -31.237664 -57.124230 -1.176078 +VERTEX_SE2 3328 -31.610848 -56.195080 1.939012 +VERTEX_SE2 3329 -31.971071 -55.280175 1.916805 +VERTEX_SE2 3330 -32.360310 -54.319381 1.916885 +VERTEX_SE2 3331 -32.725345 -53.399093 1.901732 +VERTEX_SE2 3332 -32.403469 -54.336194 -1.238738 +VERTEX_SE2 3333 -32.064852 -55.254649 -1.279873 +VERTEX_SE2 3334 -31.753773 -56.236696 -1.236462 +VERTEX_SE2 3335 -31.434607 -57.170840 -1.238306 +VERTEX_SE2 3336 -30.482315 -56.813966 0.328154 +VERTEX_SE2 3337 -29.562955 -56.500951 0.299963 +VERTEX_SE2 3338 -28.571453 -56.227635 0.292708 +VERTEX_SE2 3339 -27.576537 -55.941540 0.284887 +VERTEX_SE2 3340 -26.615891 -55.709091 0.290676 +VERTEX_SE2 3341 -25.667968 -55.433327 0.303797 +VERTEX_SE2 3342 -24.732845 -55.178259 0.320473 +VERTEX_SE2 3343 -23.794466 -54.851016 0.311289 +VERTEX_SE2 3344 -23.518270 -55.798561 -1.259471 +VERTEX_SE2 3345 -23.208332 -56.767941 -1.234299 +VERTEX_SE2 3346 -22.869767 -57.711659 -1.239844 +VERTEX_SE2 3347 -22.549695 -58.650655 -1.235757 +VERTEX_SE2 3348 -21.612874 -58.319273 0.345653 +VERTEX_SE2 3349 -20.666969 -58.026967 0.328529 +VERTEX_SE2 3350 -19.767837 -57.650344 0.308350 +VERTEX_SE2 3351 -18.853829 -57.306610 0.329716 +VERTEX_SE2 3352 -19.164112 -56.378025 1.890286 +VERTEX_SE2 3353 -19.494721 -55.462782 1.869489 +VERTEX_SE2 3354 -19.784992 -54.496976 1.859850 +VERTEX_SE2 3355 -20.046093 -53.549114 1.812499 +VERTEX_SE2 3356 -19.085127 -53.317271 0.224179 +VERTEX_SE2 3357 -18.092496 -53.101273 0.243067 +VERTEX_SE2 3358 -17.120342 -52.796996 0.230309 +VERTEX_SE2 3359 -16.135300 -52.574033 0.231184 +VERTEX_SE2 3360 -15.909901 -53.554543 -1.371526 +VERTEX_SE2 3361 -15.697062 -54.541654 -1.400442 +VERTEX_SE2 3362 -15.526597 -55.500407 -1.376736 +VERTEX_SE2 3363 -15.355440 -56.456679 -1.402452 +VERTEX_SE2 3364 -16.369813 -56.626576 -2.982237 +VERTEX_SE2 3365 -17.367480 -56.779293 -2.944588 +VERTEX_SE2 3366 -18.355627 -56.948076 -2.951658 +VERTEX_SE2 3367 -19.348558 -57.118823 -2.954590 +VERTEX_SE2 3368 -19.141444 -58.090240 -1.423095 +VERTEX_SE2 3369 -19.003550 -59.090922 -1.390768 +VERTEX_SE2 3370 -18.829606 -60.074466 -1.358817 +VERTEX_SE2 3371 -18.600744 -61.063001 -1.360817 +VERTEX_SE2 3372 -18.793808 -60.086167 1.738843 +VERTEX_SE2 3373 -18.967350 -59.104106 1.729975 +VERTEX_SE2 3374 -19.121934 -58.123048 1.750985 +VERTEX_SE2 3375 -19.279945 -57.139477 1.784459 +VERTEX_SE2 3376 -20.282490 -57.375244 -2.916126 +VERTEX_SE2 3377 -21.255106 -57.618895 -2.890334 +VERTEX_SE2 3378 -22.211946 -57.877879 -2.873181 +VERTEX_SE2 3379 -23.187894 -58.152870 -2.908527 +VERTEX_SE2 3380 -22.958844 -59.127253 -1.349482 +VERTEX_SE2 3381 -22.762606 -60.098013 -1.322608 +VERTEX_SE2 3382 -22.528702 -61.058212 -1.293766 +VERTEX_SE2 3383 -22.210899 -62.036129 -1.293909 +VERTEX_SE2 3384 -23.134626 -62.284222 -2.862944 +VERTEX_SE2 3385 -24.070126 -62.564656 -2.881086 +VERTEX_SE2 3386 -25.005440 -62.807195 -2.901266 +VERTEX_SE2 3387 -26.000395 -63.032723 -2.895646 +VERTEX_SE2 3388 -25.766470 -63.992918 -1.324201 +VERTEX_SE2 3389 -25.499320 -64.989327 -1.334944 +VERTEX_SE2 3390 -25.267206 -65.933315 -1.349045 +VERTEX_SE2 3391 -25.052577 -66.905674 -1.338066 +VERTEX_SE2 3392 -24.101867 -66.646902 0.206214 +VERTEX_SE2 3393 -23.158109 -66.475824 0.209229 +VERTEX_SE2 3394 -22.201527 -66.262181 0.174101 +VERTEX_SE2 3395 -21.234030 -66.102104 0.164364 +VERTEX_SE2 3396 -22.233890 -66.264088 -2.964851 +VERTEX_SE2 3397 -23.230733 -66.489921 -2.951281 +VERTEX_SE2 3398 -24.206589 -66.683920 -2.983106 +VERTEX_SE2 3399 -25.179635 -66.842495 -3.026021 +VERTEX_SE2 3400 -25.036923 -67.863741 -1.452135 +VERTEX_SE2 3401 -24.951406 -68.839957 -1.487472 +VERTEX_SE2 3402 -24.874228 -69.856079 -1.497957 +VERTEX_SE2 3403 -24.831151 -70.879929 -1.534664 +VERTEX_SE2 3404 -23.865390 -70.871580 0.043896 +VERTEX_SE2 3405 -22.846099 -70.807527 0.037010 +VERTEX_SE2 3406 -21.879554 -70.765233 0.033455 +VERTEX_SE2 3407 -20.884094 -70.727058 0.037125 +VERTEX_SE2 3408 -20.856081 -71.696705 -1.516225 +VERTEX_SE2 3409 -20.823770 -72.680655 -1.509572 +VERTEX_SE2 3410 -20.740561 -73.715122 -1.473426 +VERTEX_SE2 3411 -20.643619 -74.703952 -1.462805 +VERTEX_SE2 3412 -19.633322 -74.604413 0.106135 +VERTEX_SE2 3413 -18.652263 -74.484054 0.172916 +VERTEX_SE2 3414 -17.657713 -74.273302 0.196998 +VERTEX_SE2 3415 -16.695062 -74.090647 0.184076 +VERTEX_SE2 3416 -16.503514 -75.051545 -1.407934 +VERTEX_SE2 3417 -16.314694 -76.026461 -1.420215 +VERTEX_SE2 3418 -16.109835 -77.044813 -1.439083 +VERTEX_SE2 3419 -15.970401 -78.025096 -1.429151 +VERTEX_SE2 3420 -16.126505 -77.048049 1.736789 +VERTEX_SE2 3421 -16.289587 -76.050058 1.762633 +VERTEX_SE2 3422 -16.463497 -75.066429 1.745390 +VERTEX_SE2 3423 -16.646611 -74.068171 1.742175 +VERTEX_SE2 3424 -15.672502 -73.926320 0.139015 +VERTEX_SE2 3425 -14.675228 -73.771760 0.126725 +VERTEX_SE2 3426 -13.659684 -73.678480 0.148738 +VERTEX_SE2 3427 -12.663186 -73.569742 0.131311 +VERTEX_SE2 3428 -13.634051 -73.729227 -3.022984 +VERTEX_SE2 3429 -14.627398 -73.854569 -3.007869 +VERTEX_SE2 3430 -15.614547 -73.960744 -3.021040 +VERTEX_SE2 3431 -16.609884 -74.055830 -3.011054 +VERTEX_SE2 3432 -16.482118 -75.034401 -1.435399 +VERTEX_SE2 3433 -16.359655 -76.002436 -1.417632 +VERTEX_SE2 3434 -16.220019 -76.979631 -1.412297 +VERTEX_SE2 3435 -16.035766 -77.984444 -1.426219 +VERTEX_SE2 3436 -16.207008 -76.987605 1.715311 +VERTEX_SE2 3437 -16.358503 -75.969975 1.690919 +VERTEX_SE2 3438 -16.511208 -74.988153 1.681198 +VERTEX_SE2 3439 -16.620598 -74.005628 1.651423 +VERTEX_SE2 3440 -15.624379 -73.949592 0.081003 +VERTEX_SE2 3441 -14.641749 -73.880558 0.030825 +VERTEX_SE2 3442 -13.603537 -73.830222 0.024794 +VERTEX_SE2 3443 -12.608894 -73.825208 -0.001469 +VERTEX_SE2 3444 -13.629727 -73.833654 -3.138045 +VERTEX_SE2 3445 -14.627515 -73.852277 -3.138663 +VERTEX_SE2 3446 -15.596011 -73.860054 3.104595 +VERTEX_SE2 3447 -16.607796 -73.835540 3.084036 +VERTEX_SE2 3448 -16.557461 -72.841325 1.533766 +VERTEX_SE2 3449 -16.537161 -71.828952 1.518989 +VERTEX_SE2 3450 -16.476027 -70.817902 1.530472 +VERTEX_SE2 3451 -16.420734 -69.830283 1.497236 +VERTEX_SE2 3452 -16.474957 -70.795620 -1.639864 +VERTEX_SE2 3453 -16.512069 -71.814659 -1.664752 +VERTEX_SE2 3454 -16.559921 -72.803497 -1.677252 +VERTEX_SE2 3455 -16.632199 -73.806525 -1.673499 +VERTEX_SE2 3456 -16.510651 -72.846824 1.455861 +VERTEX_SE2 3457 -16.449276 -71.871912 1.457516 +VERTEX_SE2 3458 -16.325297 -70.920886 1.483718 +VERTEX_SE2 3459 -16.270664 -69.900260 1.478452 +VERTEX_SE2 3460 -15.243857 -70.005978 -0.089558 +VERTEX_SE2 3461 -14.234015 -70.112136 -0.062819 +VERTEX_SE2 3462 -13.232656 -70.210676 -0.085114 +VERTEX_SE2 3463 -12.233974 -70.261857 -0.068963 +VERTEX_SE2 3464 -12.274960 -71.250986 -1.661493 +VERTEX_SE2 3465 -12.389072 -72.210725 -1.670644 +VERTEX_SE2 3466 -12.517844 -73.186887 -1.690619 +VERTEX_SE2 3467 -12.629835 -74.150104 -1.703775 +VERTEX_SE2 3468 -12.477797 -73.136110 1.482965 +VERTEX_SE2 3469 -12.388725 -72.104838 1.485662 +VERTEX_SE2 3470 -12.244249 -71.130865 1.499177 +VERTEX_SE2 3471 -12.177732 -70.125698 1.511043 +VERTEX_SE2 3472 -12.242101 -71.138522 -1.631597 +VERTEX_SE2 3473 -12.279879 -72.160194 -1.608755 +VERTEX_SE2 3474 -12.331827 -73.156672 -1.577463 +VERTEX_SE2 3475 -12.338579 -74.163629 -1.598577 +VERTEX_SE2 3476 -13.307424 -74.114574 3.112513 +VERTEX_SE2 3477 -14.323548 -74.097541 3.064702 +VERTEX_SE2 3478 -15.332889 -74.041802 3.062145 +VERTEX_SE2 3479 -16.356565 -73.959863 3.083766 +VERTEX_SE2 3480 -16.395763 -74.971058 -1.605834 +VERTEX_SE2 3481 -16.440899 -75.989892 -1.603326 +VERTEX_SE2 3482 -16.434089 -76.978134 -1.591615 +VERTEX_SE2 3483 -16.475837 -77.989654 -1.609879 +VERTEX_SE2 3484 -17.457565 -77.931990 3.104681 +VERTEX_SE2 3485 -18.477623 -77.872188 3.117904 +VERTEX_SE2 3486 -19.465428 -77.862575 3.122126 +VERTEX_SE2 3487 -20.472230 -77.818490 -3.139675 +VERTEX_SE2 3488 -20.479037 -76.828436 1.569290 +VERTEX_SE2 3489 -20.475459 -75.822080 1.595258 +VERTEX_SE2 3490 -20.502864 -74.826124 1.605751 +VERTEX_SE2 3491 -20.566101 -73.799527 1.654654 +VERTEX_SE2 3492 -21.537428 -73.878319 -3.026071 +VERTEX_SE2 3493 -22.547520 -74.010541 -3.008620 +VERTEX_SE2 3494 -23.570642 -74.133784 -3.013800 +VERTEX_SE2 3495 -24.573822 -74.241516 -3.032331 +VERTEX_SE2 3496 -24.679654 -73.246845 1.684975 +VERTEX_SE2 3497 -24.797687 -72.238839 1.698881 +VERTEX_SE2 3498 -24.915522 -71.191381 1.695469 +VERTEX_SE2 3499 -25.076593 -70.252689 1.724867 +EDGE_SE2 0 1 1.030390 0.011350 -0.012958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1 2 1.013900 -0.058639 -0.013225 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2 3 1.027650 -0.007456 0.004833 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 4 -0.012016 1.004360 1.566790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 4 5 1.016030 0.014565 -0.016304 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 5 6 1.023890 0.006808 0.010981 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 6 7 0.957734 0.003159 0.010901 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 7 8 -1.023820 -0.013668 -3.093240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 8 9 1.023440 0.013984 -0.007802 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 9 10 1.003350 0.022250 0.023491 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 10 11 0.977245 0.019042 -0.028623 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 11 12 -0.996880 -0.025512 -3.126915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 12 13 0.990646 0.018396 -0.016519 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 13 14 0.945873 0.008893 -0.002602 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 14 15 1.000010 0.006428 0.028234 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 15 16 0.037872 -1.026090 -1.535300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 16 17 0.983790 0.019891 0.024085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 17 18 0.957199 0.029587 -0.011500 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 18 19 0.992140 0.019201 -0.007298 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 19 20 -0.045921 -1.016320 -1.539120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 20 21 0.998450 -0.005232 -0.034097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 21 22 0.988728 0.009034 -0.012914 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 22 23 0.989422 0.006982 -0.024283 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 23 24 -1.002010 -0.006263 3.139740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 24 25 1.015350 0.004913 0.000030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 25 26 1.032990 -0.001727 0.022407 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 26 27 0.989137 -0.008571 -0.020904 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 27 28 -0.048400 0.981715 1.564080 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 28 29 1.030820 -0.021271 -0.060690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 29 30 1.011920 0.016448 -0.035201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 30 31 0.991338 0.007812 0.030592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 31 32 0.008611 -0.974025 -1.569610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 32 33 1.042560 0.010669 0.022014 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 33 34 0.990826 0.016695 -0.042785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 34 35 0.995988 0.029526 -0.014411 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 35 36 -0.010774 0.996051 1.594160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 36 37 1.004990 0.011086 -0.003165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 37 38 1.038430 0.014678 -0.032321 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 38 39 1.006250 0.006744 -0.028064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 39 40 0.056163 0.984988 1.579415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 40 41 0.984656 -0.031925 0.011084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 41 42 1.002660 0.030635 0.030048 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 42 43 0.986417 -0.013098 -0.024118 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 43 44 0.978720 0.012078 -0.011743 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 44 45 0.996113 -0.040731 -0.015218 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 45 46 1.002550 -0.002163 -0.010502 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 46 47 0.999641 -0.033650 0.018807 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 47 48 -0.949748 0.011758 3.113760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 48 49 1.017390 0.012380 -0.008934 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 49 50 1.015480 0.027402 -0.019191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 50 51 1.052270 0.014738 -0.001362 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 51 52 -0.010814 -0.984360 -1.560990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 52 53 1.030710 0.008959 -0.008401 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 53 54 0.983420 0.009794 -0.030684 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 54 55 1.012040 -0.015331 0.005848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 55 56 -0.003658 -0.984986 -1.572850 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 56 57 1.031000 -0.016325 -0.016961 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 57 58 0.983393 -0.011345 -0.014840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 58 59 1.010240 0.011576 0.004329 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 59 60 0.020108 -1.008590 -1.546415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 60 61 0.992544 -0.004063 0.009069 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 61 62 0.980911 -0.012678 0.024761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 62 63 1.007650 -0.037094 -0.007451 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 63 64 -0.014542 -0.998609 -1.547390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 64 65 1.037940 -0.016831 -0.013082 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 65 66 0.991200 0.011571 -0.024952 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 66 67 0.949443 -0.015492 -0.009125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 67 68 -0.978361 -0.009274 -3.137910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 68 69 1.003670 -0.035297 0.034068 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 69 70 1.029810 0.002555 0.015001 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 70 71 1.036520 0.011807 -0.001636 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 71 72 0.003982 -0.993979 -1.584825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 72 73 0.969371 -0.030602 -0.032651 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 73 74 0.985691 0.011144 -0.001664 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 74 75 0.981205 -0.005965 0.022669 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 75 76 -0.008260 0.981841 1.564555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 76 77 1.013990 0.033209 -0.064921 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 77 78 1.027950 0.009841 0.034007 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 78 79 1.002650 -0.007743 0.009506 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 79 80 -0.010210 -0.978673 -1.538955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 80 81 1.012650 0.019201 -0.001995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 81 82 0.994241 -0.031908 -0.019756 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 82 83 1.009250 0.005910 -0.021481 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 83 84 -0.018483 1.033070 1.554995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 84 85 0.984696 0.019624 0.008775 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 85 86 0.993027 0.010799 0.010730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 86 87 0.992905 0.021361 0.011066 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 87 88 0.001218 1.040310 1.537110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 88 89 1.007670 -0.015099 0.014796 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 89 90 1.012260 -0.005391 0.030011 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 90 91 1.034570 0.002973 -0.009015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 91 92 -0.015952 0.972423 1.552590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 92 93 0.990753 0.062025 -0.014691 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 93 94 0.971423 0.014250 0.000217 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 94 95 1.022720 -0.027882 0.000365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 95 96 -0.019324 1.049340 1.572530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 96 97 1.039310 -0.013089 0.011369 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 97 98 0.993004 0.039366 -0.010571 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 98 99 1.038970 -0.023896 -0.017325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 99 100 -0.985853 -0.009798 3.131205 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 100 101 1.024650 0.031728 0.024041 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 101 102 0.993960 0.020257 -0.002407 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 102 103 1.001500 0.024148 0.001240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 103 104 -1.008670 -0.003535 -3.119555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 104 105 1.003860 0.004822 0.018774 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 105 106 0.963589 0.002141 -0.017896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 106 107 1.006700 0.025897 0.006088 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 107 108 -0.024236 -1.039040 -1.557710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 108 109 1.008390 0.024656 0.004801 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 109 110 0.995059 -0.012998 0.015867 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 110 111 0.982381 -0.004349 0.008197 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 111 112 -0.993280 0.037499 3.118685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 112 113 1.021940 -0.003415 -0.010569 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 113 114 1.022380 -0.007102 -0.011376 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 114 115 1.011560 -0.014506 -0.014457 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 115 116 -0.008907 0.980541 1.523960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 116 117 1.009140 -0.030308 -0.019198 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 117 118 0.983711 -0.005317 -0.033925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 118 119 0.985152 0.005509 0.039343 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 119 120 -1.010150 -0.053177 -3.139375 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 120 121 1.010440 -0.028117 0.036025 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 121 122 0.989826 -0.015204 0.007838 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 122 123 1.021360 0.035312 0.008159 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 123 124 -0.008542 0.950933 1.552585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 124 125 1.004770 0.016793 -0.021124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 125 126 1.026090 -0.019208 0.000006 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 126 127 0.963220 0.033064 -0.007198 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 127 128 -0.041013 1.015960 1.584960 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 128 129 1.005380 -0.013793 -0.014676 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 129 130 1.006360 -0.026231 -0.005716 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 130 131 1.003810 -0.010202 -0.043674 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 131 132 0.040168 -1.012670 -1.578770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 132 133 1.004030 -0.009232 0.000565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 133 134 0.983715 -0.003329 0.006417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 134 135 0.989074 0.039947 0.014029 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 135 136 -1.031750 0.032475 3.141330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 136 137 0.994739 -0.018182 -0.000346 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 137 138 1.021410 0.006933 -0.012528 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 138 139 1.036590 -0.008815 -0.026478 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 139 140 -1.000710 0.023227 -3.135580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 140 141 1.014140 0.004372 -0.010045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 141 142 1.036630 0.020324 0.034486 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 142 143 1.020940 0.021674 -0.000943 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 143 144 -1.001210 0.035493 -3.136465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 144 145 0.975633 0.019668 -0.014264 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 145 146 0.990986 -0.026062 0.008114 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 146 147 1.012840 -0.012720 -0.020243 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 147 148 0.011961 -1.030700 -1.540630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 148 149 1.007850 0.060060 0.025787 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 149 150 1.002510 0.001280 -0.015559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 150 151 0.975827 0.040302 0.020764 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 151 152 0.006114 1.031330 1.588000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 152 153 0.984407 0.004756 -0.045347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 153 154 0.984021 -0.025557 0.006251 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 154 155 0.958219 0.007405 0.012295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 155 156 -0.979396 0.020563 -3.099680 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 156 157 1.014320 -0.042657 0.000593 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 157 158 1.004040 -0.019473 -0.014378 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 158 159 1.001800 -0.042299 0.036304 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 159 160 -1.015340 -0.004710 -3.101715 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 160 161 0.977003 0.000202 -0.013029 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 161 162 1.028150 -0.003961 0.008721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 162 163 0.964528 0.014735 0.018703 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 163 164 -0.956570 0.008850 -3.139480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 164 165 1.002870 0.021287 -0.015990 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 165 166 0.952639 -0.035047 -0.019496 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 166 167 1.030070 0.021021 -0.001046 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 167 168 0.018523 -1.007660 -1.588815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 168 169 0.996015 -0.000706 0.021898 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 169 170 0.968562 -0.006568 -0.014378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 170 171 1.001360 -0.009948 -0.016232 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 171 172 0.006632 -1.005130 -1.590550 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 172 173 0.987193 0.002466 0.009886 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 173 174 0.971984 0.012405 -0.029066 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 174 175 1.005660 0.036410 -0.009614 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 175 176 -1.027960 -0.002102 -3.140130 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 176 177 1.007170 0.015267 0.001609 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 177 178 0.976492 0.021056 -0.000539 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 178 179 0.966935 -0.001725 0.023775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 179 180 1.007850 -0.019587 -0.019050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 180 181 0.988927 0.018030 0.000334 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 181 182 1.006010 0.006320 0.006969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 182 183 1.011060 -0.019970 -0.025594 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 183 184 0.003868 -0.968408 -1.576615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 184 185 1.030370 0.007996 -0.022705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 185 186 0.982633 0.028736 0.013888 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 186 187 1.001960 0.013313 0.037715 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 187 188 0.010186 -0.988517 -1.572330 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 188 189 0.988964 0.014161 -0.024769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 189 190 1.027400 0.011345 -0.001563 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 190 191 0.986312 0.013994 -0.010559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 191 192 0.047125 0.984631 1.613590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 192 193 0.984000 0.052823 0.007179 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 193 194 0.993458 0.016820 -0.022243 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 194 195 1.004520 0.011934 0.016757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 195 196 0.004544 0.990061 1.579355 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 196 197 1.014900 -0.011568 -0.002187 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 197 198 0.993741 0.003423 0.004484 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 198 199 1.019660 -0.032184 -0.008278 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 199 200 -0.022337 -1.015730 -1.547715 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 200 201 0.963457 0.038375 0.009501 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 201 202 0.988326 -0.001105 0.002657 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 202 203 0.990433 -0.006104 0.006328 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 203 204 0.027934 1.023810 1.564575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 204 205 0.963901 0.007727 0.000244 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 205 206 1.003560 -0.018077 0.035547 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 206 207 1.010020 -0.019375 -0.008873 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 207 208 -1.003500 0.035123 3.118220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 208 209 1.018180 0.001993 -0.000666 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 209 210 0.978662 -0.010505 -0.032735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 210 211 1.014680 0.006353 -0.006670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 211 212 0.004473 -0.990545 -1.573800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 212 213 0.966053 -0.004520 -0.018477 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 213 214 1.020000 0.017710 0.050364 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 214 215 0.998138 -0.039972 -0.013033 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 215 216 0.036956 0.980448 1.542450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 216 217 1.013180 -0.025324 -0.034378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 217 218 0.984727 0.037051 -0.023775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 218 219 0.990957 -0.004934 0.013177 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 219 220 -1.004870 0.001790 -3.112100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 220 221 1.011350 -0.033106 0.031066 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 221 222 1.013830 0.013607 -0.000131 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 222 223 1.021400 -0.005130 0.019110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 223 224 -0.985132 0.022097 -3.141205 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 224 225 1.013020 -0.029178 -0.007444 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 225 226 1.032940 0.024333 -0.012064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 226 227 0.960381 -0.029303 0.011310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 227 228 -0.002465 -1.020600 -1.594410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 228 229 0.936984 0.013013 0.009334 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 229 230 0.986469 -0.023988 0.011339 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 230 231 0.982838 -0.008844 -0.021490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 231 232 0.023141 -0.987827 -1.609160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 232 233 1.000570 0.033697 0.022897 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 233 234 0.976144 -0.018401 -0.023725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 234 235 1.019670 0.000884 0.009765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 235 236 -0.009167 1.008660 1.565300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 236 237 1.027540 -0.010776 -0.016419 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 237 238 1.023980 0.039600 -0.066882 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 238 239 0.990301 -0.016679 -0.020755 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 239 240 -0.989796 0.019005 3.099030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 240 241 0.963382 -0.000603 -0.004672 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 241 242 0.994306 -0.019836 0.016413 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 242 243 1.038120 -0.016867 -0.026819 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 243 244 -0.007591 0.961465 1.584465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 244 245 0.960155 -0.030124 0.023603 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 245 246 1.003970 -0.011043 -0.000775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 246 247 0.988968 -0.017772 -0.015002 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 247 248 1.004690 -0.003173 -0.018521 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 248 249 0.992121 0.037331 0.018905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 249 250 0.992702 0.036234 0.010180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 250 251 1.000130 0.011351 -0.011409 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 251 252 -1.029820 0.024493 -3.131615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 252 253 1.029540 -0.017626 -0.002754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 253 254 0.998637 -0.021484 -0.002483 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 254 255 1.016920 -0.015167 0.023900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 255 256 -1.004760 0.003429 -3.103780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 256 257 0.980232 -0.011121 -0.029727 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 257 258 1.005180 -0.020542 0.033515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 258 259 0.958879 -0.010994 -0.004295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 259 260 -0.998203 -0.025294 3.133530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 260 261 1.003920 0.049092 0.007939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 261 262 0.976826 0.027270 0.035274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 262 263 0.970914 0.018372 -0.017290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 263 264 0.010073 -0.994126 -1.595660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 264 265 1.032040 0.014787 0.003926 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 265 266 0.995474 -0.002145 0.014084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 266 267 0.981731 0.031345 0.012518 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 267 268 0.036493 -1.003890 -1.570590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 268 269 0.972807 -0.018199 -0.000753 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 269 270 1.026630 -0.003313 0.061100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 270 271 0.982247 -0.008291 -0.017796 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 271 272 -0.022896 1.026330 1.598050 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 272 273 1.056030 0.011267 0.033573 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 273 274 1.003210 -0.000326 -0.016986 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 274 275 0.974854 -0.026080 0.026139 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 275 276 -0.015059 1.063790 1.575120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 276 277 0.987675 -0.006952 -0.007071 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 277 278 0.980151 0.011189 -0.003553 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 278 279 1.013510 0.018151 -0.002990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 279 280 -0.018242 -0.967324 -1.586140 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 280 281 0.988024 -0.025696 0.004189 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 281 282 0.986859 -0.025799 -0.004580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 282 283 0.995969 0.030756 -0.044277 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 283 284 -1.016320 0.013961 -3.120565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 284 285 0.982895 -0.027410 0.001148 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 285 286 0.962236 0.031205 0.029062 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 286 287 1.006220 0.043033 0.017713 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 287 288 0.029808 0.982415 1.546155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 288 289 0.995180 0.000684 0.029827 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 289 290 1.030300 -0.014156 -0.041637 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 290 291 0.966349 -0.017528 0.037610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 291 292 0.002010 -0.993415 -1.584755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 292 293 1.030760 0.006563 0.039271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 293 294 0.963984 -0.009316 0.015317 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 294 295 0.984375 -0.042848 0.004996 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 295 296 0.022162 1.025920 1.615425 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 296 297 1.014890 0.001096 0.013410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 297 298 0.963497 -0.031833 -0.015943 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 298 299 1.002440 -0.003957 -0.006488 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 299 300 -0.020829 -0.995117 -1.529165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 300 301 0.967824 -0.033065 0.007024 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 301 302 0.975523 -0.013762 0.002672 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 302 303 0.973258 -0.027176 0.002606 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 303 304 0.009594 -0.986178 -1.609030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 304 305 0.996325 -0.002570 0.028859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 305 306 0.998945 0.006985 -0.002909 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 306 307 0.996313 -0.023051 -0.004914 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 307 308 -0.005678 1.004080 1.560860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 308 309 1.009140 0.008062 0.046305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 309 310 1.012000 0.015903 0.040559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 310 311 1.033710 0.005938 -0.007402 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 311 312 -0.002452 1.016190 1.598605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 312 313 0.987756 0.025956 0.022455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 313 314 0.972527 -0.004009 0.001622 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 314 315 1.033540 -0.028663 0.038180 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 315 316 -0.017823 -0.995791 -1.542395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 316 317 1.035760 -0.007201 0.032644 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 317 318 0.976907 -0.014573 -0.025545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 318 319 1.046220 0.041694 -0.006176 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 319 320 0.004385 -1.006310 -1.572200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 320 321 0.976909 0.036323 -0.000755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 321 322 1.015010 -0.000486 -0.010313 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 322 323 0.980532 -0.008712 -0.022944 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 323 324 0.010977 1.013790 1.551050 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 324 325 0.997856 0.013397 0.020398 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 325 326 1.049260 -0.016047 0.009215 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 326 327 0.976012 -0.013066 -0.004859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 327 328 -1.012850 0.041109 -3.127580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 328 329 1.008060 -0.009449 -0.003272 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 329 330 0.980827 -0.006926 0.004508 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 330 331 0.988125 0.010222 -0.006180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 331 332 0.031120 -0.967009 -1.569460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 332 333 1.012640 0.021056 -0.019065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 333 334 1.015500 -0.021394 0.037200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 334 335 1.016650 0.041173 0.016961 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 335 336 -0.035399 1.036450 1.587710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 336 337 0.992504 0.019780 -0.006438 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 337 338 0.962712 -0.019183 -0.025254 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 338 339 1.028740 -0.040955 0.002530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 339 340 -0.013820 0.999977 1.583970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 340 341 1.004210 -0.007730 0.006350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 341 342 0.996881 0.003835 -0.008607 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 342 343 1.010460 0.000203 -0.022209 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 343 344 -0.010031 -1.037880 -1.536030 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 344 345 1.022070 0.014897 -0.016479 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 345 346 1.025640 0.002468 -0.015173 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 346 347 1.010310 -0.001033 0.005201 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 347 348 -0.033171 0.960247 1.554070 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 348 349 0.983643 0.000838 -0.036369 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 349 350 1.035200 -0.000208 -0.030974 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 350 351 1.001640 -0.037102 -0.010188 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 351 352 -1.005830 -0.005212 -3.111440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 352 353 1.008620 0.001802 0.013786 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 353 354 0.984953 0.013647 0.008313 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 354 355 1.019830 0.023016 -0.016479 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 355 356 -1.001160 0.000383 -3.111315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 356 357 1.018030 0.023418 -0.000509 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 357 358 1.004940 0.013965 -0.019027 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 358 359 0.959382 -0.002248 0.002514 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 359 360 -1.065100 0.031582 3.121235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 360 361 0.997879 0.013305 -0.016881 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 361 362 1.060970 0.041019 0.018107 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 362 363 0.994578 0.007803 0.005562 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 363 364 -1.026400 -0.007016 3.139480 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 364 365 1.041980 0.010581 0.038352 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 365 366 0.974737 -0.001861 -0.030971 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 366 367 1.015520 0.019847 -0.023568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 367 368 0.028487 1.005090 1.539620 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 368 369 0.991958 -0.028192 -0.008855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 369 370 1.019980 -0.003041 -0.027093 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 370 371 0.944588 -0.016759 0.010355 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 371 372 0.022769 1.008830 1.589535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 372 373 1.037910 0.014339 0.002483 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 373 374 1.016480 0.007954 0.024533 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 374 375 0.987573 0.019284 -0.010011 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 375 376 -0.007452 -0.986353 -1.543115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 376 377 0.953791 0.002023 -0.001271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 377 378 0.966315 0.048608 -0.013940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 378 379 1.011660 0.012792 0.005418 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 379 380 -0.012450 0.989569 1.541975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 380 381 1.006950 -0.024919 0.020570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 381 382 0.998709 -0.014644 0.012757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 382 383 0.984657 0.049566 0.029896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 383 384 -0.039898 1.022750 1.572970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 384 385 0.982066 -0.000536 -0.002851 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 385 386 0.996833 0.028911 -0.003668 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 386 387 0.996147 0.007413 -0.028448 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 387 388 0.028114 0.968717 1.583580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 388 389 1.002060 -0.006186 0.010785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 389 390 0.999832 0.018561 0.028149 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 390 391 1.002970 0.017992 0.015954 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 391 392 -0.015487 -1.002530 -1.551910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 392 393 0.982092 0.013666 -0.014961 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 393 394 1.011670 -0.028848 0.013263 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 394 395 1.012710 0.026098 0.032605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 395 396 -0.039685 -1.002000 -1.604000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 396 397 0.983208 -0.027103 0.032891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 397 398 0.992204 -0.012832 0.001445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 398 399 0.995244 0.030791 0.014061 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 399 400 0.023748 -1.019090 -1.529845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 400 401 1.038320 -0.009211 -0.029477 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 401 402 1.004590 0.033654 -0.049896 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 402 403 1.006620 -0.016318 -0.021272 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 403 404 -1.023650 0.012934 -3.122620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 404 405 1.007640 0.005695 -0.015698 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 405 406 1.008700 -0.012120 -0.012596 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 406 407 0.971751 0.012841 0.059359 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 407 408 -0.015585 -0.987421 -1.579500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 408 409 0.990590 -0.000610 -0.009762 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 409 410 1.005240 -0.020540 0.010616 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 410 411 0.976917 -0.011584 -0.021674 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 411 412 0.025285 0.998297 1.560460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 412 413 0.981726 -0.010608 -0.037551 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 413 414 0.969233 -0.003648 -0.003003 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 414 415 1.016620 -0.016343 0.013318 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 415 416 -1.004830 0.006344 3.134930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 416 417 0.982766 -0.035210 0.030624 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 417 418 1.019270 -0.019337 -0.019842 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 418 419 1.003280 0.014598 0.015980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 419 420 -0.030091 1.047650 1.568065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 420 421 0.975289 -0.032809 0.006293 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 421 422 0.951750 0.022674 0.023257 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 422 423 1.006470 -0.051107 -0.002371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 423 424 0.979416 0.008789 -0.007823 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 424 425 0.982439 0.046866 -0.031498 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 425 426 0.968721 -0.037773 -0.055447 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 426 427 0.998414 -0.023554 -0.034427 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 427 428 -0.003846 1.027870 1.538600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 428 429 0.967217 0.005981 0.003039 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 429 430 1.029180 0.006210 -0.012141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 430 431 0.969919 -0.004921 -0.026727 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 431 432 0.025001 -0.963741 -1.610100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 432 433 0.998646 0.039816 0.031679 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 433 434 0.998116 0.019787 -0.036985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 434 435 1.008830 0.005636 -0.051170 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 435 436 -0.042064 -0.993330 -1.598585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 436 437 0.940503 0.012754 0.035217 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 437 438 0.990735 -0.006990 -0.001060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 438 439 0.960341 0.018591 -0.001521 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 439 440 -0.007788 0.996636 1.603575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 440 441 1.001200 -0.000750 -0.000755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 441 442 1.002400 0.025122 -0.014042 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 442 443 1.018670 0.014033 0.011523 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 443 444 -0.952078 -0.023855 3.137640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 444 445 1.006350 0.001737 -0.037591 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 445 446 1.016670 0.020104 0.026524 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 446 447 0.978185 -0.009521 0.008526 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 447 448 -0.003031 -0.985923 -1.552050 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 448 449 1.039490 0.005503 0.045449 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 449 450 1.003640 0.028308 -0.032817 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 450 451 0.999867 -0.023452 0.008914 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 451 452 -1.024970 0.032897 -3.138005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 452 453 1.013370 -0.000974 -0.044911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 453 454 1.012290 0.025029 0.009442 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 454 455 0.999904 -0.005136 -0.023239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 455 456 -1.012020 0.058263 3.122075 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 456 457 1.004080 0.005425 0.022569 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 457 458 1.001440 -0.005360 -0.002077 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 458 459 1.016520 -0.009668 -0.015492 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 459 460 -1.004420 0.014216 3.106970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 460 461 0.994726 -0.030121 0.036119 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 461 462 1.049190 0.015648 -0.030979 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 462 463 0.997902 -0.008807 -0.013352 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 463 464 0.015936 0.981001 1.595455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 464 465 0.966331 -0.029990 0.012968 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 465 466 1.020520 0.034792 0.002956 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 466 467 1.005420 -0.007639 -0.009044 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 467 468 0.013268 -0.990512 -1.566435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 468 469 1.016840 0.007976 -0.020045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 469 470 0.953815 0.024356 -0.042851 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 470 471 0.992383 -0.020576 0.008559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 471 472 -0.984259 -0.004032 -3.133660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 472 473 1.018140 0.014553 -0.001173 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 473 474 1.022920 -0.031999 -0.021120 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 474 475 1.024770 0.002970 -0.034222 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 475 476 -1.017360 0.024313 3.104400 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 476 477 0.997066 0.023113 -0.041605 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 477 478 1.022230 0.029008 -0.011084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 478 479 0.994768 0.012139 0.001519 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 479 480 -1.017500 0.009742 -3.130150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 480 481 0.978153 -0.019200 0.019259 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 481 482 0.989011 0.005481 -0.012002 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 482 483 1.040520 -0.026045 0.003683 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 483 484 0.033499 1.028000 1.547770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 484 485 1.058610 -0.005959 0.014549 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 485 486 0.979688 0.019445 -0.004986 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 486 487 1.025130 0.001318 0.012656 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 487 488 0.023272 -0.939869 -1.582470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 488 489 0.981954 -0.004126 -0.005900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 489 490 1.016350 0.005731 0.001790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 490 491 1.001550 0.005493 0.004593 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 491 492 -0.047867 -0.991252 -1.560850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 492 493 0.994269 0.009541 -0.041813 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 493 494 0.964862 -0.001774 -0.026656 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 494 495 0.978857 0.026045 0.077976 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 495 496 -0.966547 0.029122 -3.108615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 496 497 0.981790 -0.047632 -0.016837 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 497 498 0.975014 -0.025418 -0.001097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 498 499 1.008240 -0.038639 -0.039210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 499 500 -0.993365 -0.011848 3.125295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 500 501 0.985881 -0.017931 0.014825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 501 502 0.983942 -0.008486 0.003883 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 502 503 1.012350 -0.002216 0.028561 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 503 504 -0.975362 0.004588 3.130390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 504 505 0.941082 0.012088 0.008236 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 505 506 0.999673 0.011588 -0.003188 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 506 507 0.986716 -0.048182 -0.004582 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 507 508 0.010333 -0.975784 -1.524560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 508 509 1.001840 -0.004398 -0.041126 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 509 510 1.029530 -0.010107 0.048510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 510 511 1.028260 -0.001349 0.020444 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 511 512 -0.009511 -1.011600 -1.600770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 512 513 0.991876 0.018149 0.009448 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 513 514 1.035620 -0.002330 -0.017979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 514 515 0.998747 0.018136 -0.013468 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 515 516 -0.986452 0.023140 3.132650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 516 517 0.960760 -0.022505 0.008110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 517 518 1.027650 0.025763 0.007439 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 518 519 1.047970 0.033121 -0.001317 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 519 520 0.020790 0.979847 1.573490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 520 521 0.987088 0.044353 -0.008202 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 521 522 1.006620 -0.031561 -0.048698 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 522 523 1.022710 -0.011468 0.008737 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 523 524 -0.972122 0.052501 -3.133400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 524 525 0.954726 -0.002495 -0.009712 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 525 526 1.012880 0.020793 0.015543 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 526 527 1.004890 -0.019865 0.006705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 527 528 -1.017210 0.017228 -3.107545 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 528 529 1.000990 -0.012724 -0.006414 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 529 530 1.013720 -0.018745 -0.033217 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 530 531 1.037470 0.018059 0.030871 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 531 532 -0.056600 1.004360 1.561075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 532 533 1.039940 0.014157 0.003008 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 533 534 0.997099 0.014517 0.013188 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 534 535 1.002710 -0.000324 0.040172 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 535 536 -0.993886 -0.012421 3.140490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 536 537 1.002900 -0.006539 0.004346 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 537 538 0.950702 0.007097 -0.003958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 538 539 1.001820 -0.027064 -0.017463 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 539 540 -1.011180 0.045848 -3.134480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 540 541 1.009020 0.033468 0.016366 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 541 542 1.014220 0.040327 0.005702 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 542 543 1.045150 -0.004510 0.013703 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 543 544 -0.019705 0.977433 1.570370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 544 545 0.999211 -0.010477 0.011571 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 545 546 0.965988 -0.069469 0.026705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 546 547 1.002810 -0.033404 -0.039340 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 547 548 -0.018015 1.030500 1.581370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 548 549 0.969801 -0.006510 0.012259 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 549 550 1.022280 0.035108 -0.031521 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 550 551 1.016250 -0.011384 -0.022246 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 551 552 -0.004135 0.988278 1.519850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 552 553 0.988505 0.034792 -0.014058 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 553 554 0.988890 -0.020331 -0.004116 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 554 555 1.039530 0.002386 0.014488 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 555 556 -0.975244 -0.044017 3.136875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 556 557 0.997493 0.011532 -0.004659 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 557 558 1.034600 0.002405 0.001464 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 558 559 1.005780 -0.007456 -0.013761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 559 560 0.014353 0.993729 1.535380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 560 561 0.945928 0.030304 0.008900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 561 562 1.049830 0.000941 -0.030860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 562 563 0.978300 -0.028669 0.012776 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 563 564 0.979431 -0.011205 -0.015774 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 564 565 1.011580 0.039604 0.007707 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 565 566 0.998037 0.033279 -0.018094 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 566 567 0.992544 0.018243 -0.007129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 567 568 -1.034940 -0.016931 3.128205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 568 569 0.991157 -0.004422 0.003391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 569 570 1.023690 0.005726 0.032515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 570 571 1.011190 -0.055261 0.019343 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 571 572 0.009183 1.033210 1.510360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 572 573 1.009230 -0.029052 0.021913 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 573 574 0.983956 0.023784 -0.011560 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 574 575 1.008510 -0.015364 0.045743 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 575 576 -0.005013 0.985986 1.588980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 576 577 1.004740 0.015413 -0.000812 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 577 578 0.972946 -0.010204 -0.041335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 578 579 1.011840 0.015859 -0.009478 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 579 580 0.012159 1.005810 1.558610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 580 581 0.960362 -0.003000 0.009084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 581 582 0.984156 0.038546 -0.009119 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 582 583 1.009430 -0.022616 0.012541 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 583 584 0.016539 0.970553 1.579485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 584 585 0.994916 0.060433 0.012629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 585 586 0.976859 0.022960 -0.005840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 586 587 1.037400 0.017438 -0.063238 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 587 588 -0.011946 -1.001510 -1.580835 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 588 589 1.010220 -0.003385 0.003859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 589 590 1.023730 0.021342 0.025410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 590 591 0.996862 0.003930 0.010584 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 591 592 -0.022830 -0.995505 -1.632170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 592 593 0.982909 0.031980 -0.015591 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 593 594 1.000920 -0.020177 0.001732 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 594 595 1.008590 -0.006726 -0.029103 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 595 596 0.019768 -0.985265 -1.587730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 596 597 1.034010 0.019502 -0.023400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 597 598 1.011450 0.016735 0.010056 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 598 599 1.019050 0.022481 -0.000472 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 599 600 0.016243 -0.973859 -1.533590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 600 601 1.005280 -0.031103 0.013178 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 601 602 1.013270 -0.013873 -0.000070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 602 603 0.993865 -0.003195 -0.016873 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 603 604 -0.038145 1.012470 1.565310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 604 605 1.015250 -0.037720 0.031826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 605 606 0.982427 0.001353 0.047715 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 606 607 1.007390 -0.003452 -0.006807 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 607 608 -0.019641 1.019490 1.556250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 608 609 1.003030 0.028594 -0.007686 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 609 610 1.002450 0.022603 -0.026495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 610 611 0.990604 0.000695 -0.008268 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 611 612 -0.986214 -0.007386 3.101555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 612 613 1.001640 -0.035231 0.001834 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 613 614 1.060820 -0.011337 -0.022340 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 614 615 1.040500 0.022684 -0.006443 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 615 616 -1.011760 0.003575 3.134620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 616 617 0.992042 -0.006514 -0.033881 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 617 618 0.979442 -0.010875 0.027645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 618 619 0.965590 0.019012 -0.003698 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 619 620 0.044668 -0.973957 -1.528020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 620 621 1.013880 0.033922 -0.024276 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 621 622 1.038920 0.033279 -0.020289 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 622 623 1.000810 -0.026895 -0.012385 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 623 624 -1.006610 0.032005 -3.131535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 624 625 1.037040 -0.021139 -0.000237 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 625 626 1.018190 -0.005540 0.036292 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 626 627 0.991018 -0.030638 -0.011376 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 627 628 0.029371 0.979917 1.576235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 628 629 1.007170 0.018316 0.026859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 629 630 0.977038 -0.008609 0.020810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 630 631 0.992497 0.011267 0.028576 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 631 632 -0.042641 0.992474 1.568460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 632 633 0.975863 -0.029947 0.017924 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 633 634 0.992509 -0.002072 0.008720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 634 635 0.945528 0.005322 -0.040582 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 635 636 -0.975416 -0.006170 3.122960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 636 637 0.995577 0.007725 -0.013082 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 637 638 1.003610 -0.018862 0.015496 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 638 639 1.012210 -0.010822 0.018884 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 639 640 0.003714 -0.982351 -1.565070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 640 641 1.003540 -0.015078 -0.021972 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 641 642 1.042620 -0.017805 0.007307 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 642 643 0.976767 -0.049280 0.007847 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 643 644 -1.022690 -0.028873 3.126245 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 644 645 0.995782 -0.031711 0.002547 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 645 646 0.942105 0.006327 -0.000921 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 646 647 0.998559 -0.012811 -0.007529 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 647 648 0.025428 1.015770 1.571460 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 648 649 1.001080 -0.026210 0.007356 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 649 650 1.023100 0.007027 -0.005321 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 650 651 1.003000 0.041838 -0.051576 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 651 652 -0.003830 1.063120 1.590070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 652 653 0.954376 0.002667 0.018746 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 653 654 1.020920 0.049047 -0.043360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 654 655 0.964102 -0.012500 0.020161 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 655 656 -0.997866 0.024020 -3.129040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 656 657 0.975973 -0.046230 -0.040216 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 657 658 0.975451 -0.018069 -0.038447 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 658 659 0.997989 0.012739 0.038856 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 659 660 0.019394 1.024830 1.578650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 660 661 0.989672 0.001585 -0.023991 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 661 662 0.991001 0.008239 0.027088 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 662 663 0.945483 -0.011529 -0.000711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 663 664 0.008842 -1.004320 -1.610390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 664 665 1.028750 0.001385 0.015503 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 665 666 1.002250 -0.035436 0.013343 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 666 667 0.986362 -0.008567 -0.017430 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 667 668 -0.968012 0.000649 -3.117945 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 668 669 1.009510 0.022850 0.013732 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 669 670 1.000450 -0.001354 0.014069 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 670 671 1.029680 -0.026154 -0.013755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 671 672 -0.986864 0.005666 -3.127890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 672 673 1.017910 0.004486 0.049101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 673 674 0.991045 0.010156 0.006742 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 674 675 0.969293 0.008976 0.017350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 675 676 -1.011910 0.001695 3.114150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 676 677 0.993077 -0.020763 0.004501 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 677 678 0.983459 0.005819 -0.020351 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 678 679 0.968561 -0.028992 0.022669 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 679 680 -0.005768 0.997766 1.555370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 680 681 0.934790 0.031256 0.025923 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 681 682 1.028430 0.005228 -0.023258 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 682 683 0.991521 0.013558 -0.000009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 683 684 0.007229 -1.028960 -1.577990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 684 685 1.010280 0.009158 -0.016673 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 685 686 0.994562 0.033297 0.007101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 686 687 0.985423 0.013237 0.042460 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 687 688 0.025280 0.992311 1.535910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 688 689 0.970739 0.007772 0.038494 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 689 690 1.011840 -0.013893 0.025468 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 690 691 0.979903 0.009947 -0.001700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 691 692 0.021886 -0.981125 -1.645040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 692 693 1.001850 0.032024 0.001600 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 693 694 0.992716 0.018271 0.009756 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 694 695 1.009200 -0.002560 0.021934 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 695 696 0.006115 -0.980741 -1.589070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 696 697 1.020080 -0.019358 0.015155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 697 698 0.987487 -0.044401 0.013763 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 698 699 0.982945 -0.043590 0.014090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 699 700 0.020969 1.031980 1.602670 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 700 701 1.009090 0.018698 -0.020672 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 701 702 0.986430 0.007926 -0.032911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 702 703 1.006550 0.000959 0.003622 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 703 704 0.007158 1.016300 1.568850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 704 705 0.966333 -0.030530 -0.016587 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 705 706 1.039260 -0.015495 0.025015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 706 707 1.042810 -0.019428 -0.005891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 707 708 0.017015 0.997363 1.581475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 708 709 0.985795 0.019493 0.031018 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 709 710 1.005200 0.027450 -0.011637 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 710 711 1.012760 0.033621 -0.041894 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 711 712 0.043873 -0.976466 -1.582655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 712 713 0.990925 0.008425 -0.000601 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 713 714 0.997585 -0.016563 -0.012218 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 714 715 0.979214 -0.007571 0.001520 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 715 716 -0.971446 0.009047 -3.119450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 716 717 0.991090 0.008793 0.002176 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 717 718 1.012700 -0.005897 -0.007131 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 718 719 1.012630 -0.003270 -0.020826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 719 720 0.005524 0.997428 1.553500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 720 721 0.997620 -0.014073 0.009890 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 721 722 0.995845 -0.016613 0.006880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 722 723 1.018200 -0.028338 0.003909 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 723 724 -1.000240 0.007227 3.107725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 724 725 0.978300 0.007168 -0.019123 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 725 726 0.980414 -0.004706 -0.023906 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 726 727 0.990521 -0.012905 -0.016796 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 727 728 0.008932 1.037480 1.576850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 728 729 1.002080 0.023710 -0.000144 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 729 730 0.997136 -0.006320 -0.004650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 730 731 1.003010 0.041649 -0.009632 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 731 732 0.000834 0.969341 1.536050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 732 733 0.995749 -0.022235 0.010748 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 733 734 0.999684 0.009323 -0.037912 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 734 735 1.006030 0.026924 0.016426 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 735 736 -0.001394 1.050880 1.587540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 736 737 1.023900 0.062019 0.011616 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 737 738 0.981820 -0.003497 0.011620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 738 739 1.022740 0.000711 0.015115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 739 740 -1.009400 -0.026484 -3.113550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 740 741 0.998688 0.037253 0.030588 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 741 742 0.997672 0.044447 0.015709 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 742 743 0.996682 -0.000123 0.009770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 743 744 0.022514 -1.007280 -1.590870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 744 745 0.985984 0.015937 0.000141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 745 746 1.024470 0.026028 0.000908 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 746 747 0.984640 -0.005815 -0.005459 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 747 748 -1.003450 -0.017299 3.128340 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 748 749 1.032330 0.022276 -0.022940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 749 750 1.001240 0.069896 -0.003281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 750 751 0.991926 0.008162 0.006052 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 751 752 -0.963229 0.040862 -3.132550 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 752 753 0.979305 -0.040392 0.000959 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 753 754 0.990029 -0.020602 -0.044781 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 754 755 0.971995 0.049572 -0.047054 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 755 756 -0.002653 0.956387 1.553640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 756 757 1.014970 -0.010330 -0.010349 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 757 758 0.983225 -0.000971 0.009610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 758 759 0.959020 0.054866 0.034202 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 759 760 0.032087 0.982395 1.587820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 760 761 0.970381 -0.032533 0.000709 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 761 762 1.004590 -0.022634 0.005056 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 762 763 1.016810 -0.031793 -0.003683 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 763 764 -0.997108 0.016051 3.136265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 764 765 1.025330 0.011796 0.003764 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 765 766 1.017660 0.008162 0.012731 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 766 767 1.001140 -0.024474 0.005017 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 767 768 0.993169 0.018425 -0.027882 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 768 769 1.006810 -0.028884 -0.027158 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 769 770 0.985958 0.019859 0.014417 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 770 771 1.016570 0.028870 0.005611 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 771 772 -0.012213 -1.018400 -1.587105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 772 773 0.951753 0.031002 0.016600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 773 774 0.980789 -0.016029 -0.002220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 774 775 1.005590 -0.006939 0.026739 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 775 776 -0.003607 -1.002060 -1.526570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 776 777 1.001210 -0.014193 0.030759 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 777 778 0.971573 0.016274 -0.013464 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 778 779 1.005350 -0.026215 -0.026285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 779 780 0.033801 -0.972418 -1.571730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 780 781 1.016220 0.064318 -0.030915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 781 782 1.007470 -0.008757 0.014380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 782 783 1.021860 -0.032050 -0.022720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 783 784 -0.011854 -1.011250 -1.539740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 784 785 0.995259 -0.025972 -0.006496 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 785 786 1.010820 0.062326 -0.009030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 786 787 0.988623 -0.074377 0.004106 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 787 788 0.027532 1.013360 1.560530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 788 789 0.974831 0.014700 -0.019072 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 789 790 0.997521 -0.032829 -0.013860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 790 791 0.994170 0.007855 0.021466 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 791 792 0.003983 -0.927390 -1.581300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 792 793 1.009220 0.029037 -0.011545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 793 794 1.020020 0.015056 -0.008682 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 794 795 0.997417 0.053276 0.042176 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 795 796 -0.020532 0.997830 1.596690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 796 797 1.000990 0.011217 0.025844 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 797 798 1.027330 -0.015621 -0.031384 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 798 799 0.988796 -0.008200 -0.031626 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 799 800 0.007906 -1.048560 -1.570000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 800 801 1.011930 0.019082 -0.015248 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 801 802 1.018650 -0.002702 0.045793 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 802 803 0.978156 0.026794 0.015776 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 803 804 0.006908 1.003810 1.551790 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 804 805 0.981410 -0.036441 0.025613 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 805 806 1.020650 0.002740 0.003792 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 806 807 1.030630 0.002836 -0.004444 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 807 808 0.029692 -1.011180 -1.550020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 808 809 1.006860 -0.032231 0.001516 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 809 810 0.979691 0.019649 0.000979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 810 811 1.026410 -0.007872 -0.005246 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 811 812 -0.010088 0.964580 1.578490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 812 813 1.038790 -0.012791 0.006411 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 813 814 0.985668 -0.009410 -0.023242 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 814 815 1.031460 0.019294 0.011159 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 815 816 -0.022429 0.946896 1.530280 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 816 817 0.998178 0.030521 0.041857 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 817 818 0.977319 -0.004254 0.005036 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 818 819 1.036280 -0.012442 -0.000208 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 819 820 -0.982892 0.046713 3.136485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 820 821 0.990217 0.007036 -0.009849 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 821 822 0.985782 -0.018741 0.017336 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 822 823 0.994255 -0.011819 0.029790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 823 824 0.009135 -1.017030 -1.591765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 824 825 0.972358 -0.046804 -0.008429 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 825 826 1.037470 0.023217 -0.017743 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 826 827 1.022980 0.013021 -0.016271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 827 828 0.955055 -0.002222 0.012294 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 828 829 0.996371 0.011154 0.001318 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 829 830 0.964886 -0.008406 -0.030324 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 830 831 0.977235 0.017999 0.027064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 831 832 -1.013730 0.046226 -3.134860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 832 833 1.025160 -0.014840 -0.000148 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 833 834 0.983204 0.009940 -0.068580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 834 835 0.956283 0.003696 -0.037553 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 835 836 -0.002052 0.984820 1.547140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 836 837 1.010010 -0.008587 -0.010127 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 837 838 1.007870 -0.028311 -0.060065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 838 839 1.016570 0.015337 -0.029991 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 839 840 -0.009880 -1.040200 -1.583980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 840 841 1.010090 -0.005629 0.030830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 841 842 0.979822 -0.012693 0.001153 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 842 843 1.009610 -0.026547 0.004939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 843 844 -0.030466 1.016170 1.543160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 844 845 0.961012 -0.007716 -0.005205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 845 846 1.034480 0.024719 0.000319 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 846 847 1.009230 0.007096 0.028040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 847 848 -1.023170 0.025991 -3.094760 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 848 849 0.994705 -0.048113 -0.048967 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 849 850 1.008590 -0.015833 0.020560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 850 851 0.989280 0.021248 0.033789 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 851 852 0.986647 -0.003991 0.018819 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 852 853 1.021190 0.012375 0.038805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 853 854 1.029550 0.029288 -0.019992 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 854 855 0.996823 -0.001816 0.032302 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 855 856 0.046535 -0.948973 -1.548955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 856 857 1.001230 0.004266 0.009923 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 857 858 0.972099 0.022451 -0.026974 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 858 859 1.000820 -0.004003 0.040936 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 859 860 -0.970762 -0.015314 -3.105190 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 860 861 0.945903 -0.037483 0.036429 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 861 862 0.973033 -0.026668 -0.015220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 862 863 1.010870 0.000362 0.007357 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 863 864 -1.010660 -0.029732 3.120610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 864 865 0.985097 0.004563 -0.025417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 865 866 1.003460 0.014730 -0.010455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 866 867 0.986940 0.017076 0.024110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 867 868 -1.015950 0.014525 -3.122040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 868 869 0.988295 0.006107 0.057285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 869 870 1.030860 0.007870 0.026255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 870 871 0.982089 -0.027989 -0.009368 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 871 872 1.015240 0.001306 -0.016033 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 872 873 0.963504 -0.000748 -0.035186 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 873 874 1.020320 -0.039293 0.010885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 874 875 1.006250 0.013510 0.012781 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 875 876 0.005939 0.998728 1.536670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 876 877 0.996531 -0.010340 -0.014049 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 877 878 1.010440 -0.010915 0.002885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 878 879 1.005120 0.005034 -0.013775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 879 880 -1.011660 -0.017694 3.137935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 880 881 1.013760 0.026357 -0.016262 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 881 882 0.992255 -0.018599 -0.018767 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 882 883 1.010790 -0.024490 -0.026112 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 883 884 -0.980522 -0.009670 -3.135255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 884 885 0.971092 0.025422 -0.016878 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 885 886 1.015010 -0.006540 -0.040465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 886 887 1.007030 0.025566 0.030036 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 887 888 -0.013630 -0.990318 -1.544840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 888 889 1.008030 -0.017260 0.015232 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 889 890 1.041970 -0.010797 0.033399 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 890 891 0.997600 -0.017352 -0.002539 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 891 892 -1.014390 0.002833 -3.133795 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 892 893 0.988582 0.020303 0.072912 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 893 894 0.991366 0.012744 0.041042 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 894 895 1.011680 -0.027796 -0.006238 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 895 896 -0.021879 -1.013650 -1.559830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 896 897 1.008310 0.014436 -0.044667 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 897 898 1.012700 0.018705 0.009213 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 898 899 1.001580 -0.018989 -0.007467 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 899 900 -1.013340 0.033524 3.136015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 900 901 0.985189 0.012052 -0.053651 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 901 902 1.008790 -0.062573 -0.057546 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 902 903 0.983117 0.010422 0.003997 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 903 904 -0.010605 1.007890 1.546090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 904 905 0.994859 0.038067 -0.001201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 905 906 1.009490 0.005822 -0.019647 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 906 907 0.983410 0.019986 -0.011533 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 907 908 -0.011362 0.985697 1.552670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 908 909 0.977553 0.023940 0.040616 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 909 910 0.981520 -0.024928 -0.008469 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 910 911 1.047180 0.003709 -0.016816 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 911 912 -0.973460 0.018141 3.137475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 912 913 1.006320 -0.001288 0.011929 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 913 914 0.988292 0.035110 0.012630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 914 915 1.017410 0.017055 0.021406 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 915 916 0.013883 0.984675 1.558080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 916 917 0.983509 -0.001759 -0.039515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 917 918 0.985475 -0.004414 -0.020370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 918 919 1.007020 0.002466 -0.012661 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 919 920 -0.974853 0.017800 -3.131185 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 920 921 0.993411 0.011663 -0.016474 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 921 922 0.998893 0.001665 -0.004141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 922 923 1.010580 -0.016701 -0.019645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 923 924 -1.006320 0.001963 3.094065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 924 925 0.966906 -0.004740 0.036199 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 925 926 0.985308 -0.017149 -0.046829 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 926 927 0.993717 0.005518 0.017279 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 927 928 0.039567 -1.013200 -1.553310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 928 929 0.991153 0.006457 0.010744 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 929 930 0.984083 0.050227 0.007558 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 930 931 1.029210 0.045379 0.000182 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 931 932 0.011641 1.044140 1.574820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 932 933 0.990539 0.019388 0.041614 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 933 934 1.001440 0.059989 0.000061 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 934 935 1.003610 0.019905 0.029256 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 935 936 -1.015840 -0.042586 3.123230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 936 937 0.973764 0.017339 0.016399 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 937 938 1.030580 -0.014930 0.024234 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 938 939 0.992721 -0.018886 -0.029783 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 939 940 1.027390 -0.017703 -0.071112 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 940 941 1.014510 0.005764 -0.003062 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 941 942 0.957423 0.015383 -0.020138 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 942 943 1.014740 -0.027093 -0.018868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 943 944 0.018189 -1.007440 -1.562940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 944 945 0.999112 -0.037905 -0.018573 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 945 946 1.006160 -0.004750 -0.012780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 946 947 0.957966 0.016582 -0.017057 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 947 948 0.051989 -1.002980 -1.554180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 948 949 1.006310 -0.048732 -0.014741 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 949 950 0.987867 -0.039697 0.008861 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 950 951 0.975686 0.009267 0.003721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 951 952 -1.009150 0.006354 -3.134805 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 952 953 0.994810 -0.014083 0.007272 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 953 954 1.035920 -0.032541 -0.014527 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 954 955 0.998326 0.012573 0.003949 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 955 956 0.016093 1.003390 1.570815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 956 957 1.037130 -0.036420 0.006325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 957 958 1.029130 0.002036 0.000427 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 958 959 1.014620 -0.003183 0.013824 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 959 960 -1.006980 -0.032221 3.117090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 960 961 1.013900 0.037610 -0.010864 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 961 962 0.998172 0.007257 -0.022361 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 962 963 1.035800 0.008178 0.012700 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 963 964 -0.979138 -0.005215 3.102035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 964 965 0.970731 -0.003109 0.013460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 965 966 1.027580 0.002667 -0.003868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 966 967 1.008660 0.001904 -0.021144 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 967 968 -1.003200 -0.000799 -3.113135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 968 969 1.044560 -0.004844 -0.001000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 969 970 0.991370 0.005882 -0.039291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 970 971 1.015070 -0.023658 -0.016832 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 971 972 0.017434 0.985974 1.562040 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 972 973 1.000220 -0.021453 0.007948 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 973 974 0.961596 -0.001908 -0.015097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 974 975 0.983545 0.002732 0.028356 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 975 976 0.952546 -0.006796 0.008833 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 976 977 1.014950 -0.043991 -0.010044 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 977 978 0.965748 0.046823 0.007869 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 978 979 0.999882 -0.062399 0.010906 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 979 980 -1.024780 -0.010908 -3.116160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 980 981 1.008640 0.043769 -0.007304 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 981 982 0.978881 -0.013855 -0.021976 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 982 983 0.987210 0.006621 0.027435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 983 984 -1.005460 0.021479 -3.128745 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 984 985 0.972659 -0.004309 -0.027364 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 985 986 0.975939 -0.000117 0.038212 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 986 987 0.989461 0.011060 0.007876 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 987 988 -0.009158 -0.980544 -1.579570 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 988 989 1.009980 -0.023095 -0.002784 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 989 990 1.024430 -0.010808 0.036988 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 990 991 1.028330 -0.035048 -0.020550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 991 992 0.009767 -1.013340 -1.529120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 992 993 1.048240 0.005430 0.003571 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 993 994 0.970856 0.025011 0.010708 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 994 995 0.982229 -0.009626 0.050309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 995 996 0.036548 0.999152 1.542280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 996 997 1.004190 0.028832 0.006535 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 997 998 0.988454 -0.004041 -0.024310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 998 999 1.045830 -0.040305 0.031252 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 999 1000 -1.008730 0.018329 3.138325 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1000 1001 0.996060 0.013441 0.020844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1001 1002 1.015270 0.008671 -0.056611 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1002 1003 1.056570 -0.003286 -0.010214 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1003 1004 0.015299 -0.948416 -1.527165 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1004 1005 1.024300 -0.017376 0.038724 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1005 1006 0.993608 0.013316 0.007206 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1006 1007 1.026200 -0.020910 -0.003615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1007 1008 -0.005112 -0.966305 -1.593820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1008 1009 1.000840 -0.008642 -0.007089 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1009 1010 1.012310 -0.008460 0.007786 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1010 1011 1.043980 -0.016093 0.001664 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1011 1012 -0.015606 1.010210 1.543660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1012 1013 0.995509 -0.004987 0.037469 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1013 1014 1.020270 -0.075242 0.009129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1014 1015 0.998617 0.001806 0.000400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1015 1016 -0.014452 -0.958189 -1.583070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1016 1017 0.982184 -0.013000 0.002678 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1017 1018 1.004360 0.019792 -0.014883 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1018 1019 0.973472 0.015100 0.029194 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1019 1020 -0.990701 -0.029397 3.122015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1020 1021 0.996209 -0.010105 -0.013308 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1021 1022 0.983504 -0.011672 0.000675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1022 1023 0.959857 -0.007815 0.034733 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1023 1024 -0.959429 0.029045 -3.137805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1024 1025 0.990506 -0.033231 -0.008366 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1025 1026 1.027880 0.029842 -0.005509 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1026 1027 0.994491 -0.018112 -0.051438 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1027 1028 -0.005900 -0.960301 -1.540360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1028 1029 0.982557 -0.035708 0.009338 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1029 1030 0.962889 0.011240 0.038892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1030 1031 1.007790 0.002768 0.003037 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1031 1032 -0.004540 1.002160 1.576910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1032 1033 0.999924 0.008348 0.004060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1033 1034 1.004900 0.010037 0.006136 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1034 1035 0.969195 -0.009363 0.026254 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1035 1036 -0.026784 1.015390 1.615220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1036 1037 0.975133 0.057348 0.002507 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1037 1038 0.999632 0.009426 -0.026833 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1038 1039 0.987938 -0.002811 -0.002124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1039 1040 -0.022064 1.004440 1.552235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1040 1041 1.007050 0.016724 0.028210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1041 1042 0.986172 -0.003955 -0.019524 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1042 1043 1.000040 -0.017642 -0.027572 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1043 1044 0.977709 -0.022104 0.012969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1044 1045 0.980447 -0.024326 0.003104 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1045 1046 1.009830 0.035565 0.024247 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1046 1047 0.992586 -0.002268 0.022069 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1047 1048 0.009983 0.969131 1.597040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1048 1049 1.043130 -0.005630 -0.042812 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1049 1050 1.014870 -0.007756 -0.026568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1050 1051 1.050030 -0.023386 0.046715 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1051 1052 0.004770 -0.989537 -1.615800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1052 1053 0.970495 0.002081 -0.012026 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1053 1054 0.996124 0.011043 0.006031 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1054 1055 0.950608 -0.002890 0.054185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1055 1056 -1.046250 0.007421 3.128150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1056 1057 0.959592 -0.028664 0.020656 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1057 1058 1.001220 0.018862 0.022113 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1058 1059 0.997045 -0.025753 -0.035261 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1059 1060 -0.988929 -0.028543 -3.137750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1060 1061 0.999090 -0.015268 0.006229 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1061 1062 1.000980 -0.020996 -0.060757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1062 1063 0.969544 0.007409 0.052780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1063 1064 -0.015952 1.013600 1.538390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1064 1065 1.002310 0.007504 -0.016291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1065 1066 0.981333 -0.049274 0.006301 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1066 1067 1.007070 -0.013808 -0.025215 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1067 1068 -1.026630 0.017566 -3.129195 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1068 1069 0.994086 -0.019100 0.022458 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1069 1070 0.969184 0.001911 -0.031885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1070 1071 1.020090 -0.015151 -0.007311 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1071 1072 -1.049050 -0.044531 -3.119260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1072 1073 0.979133 0.034741 -0.022020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1073 1074 1.010110 -0.042504 0.016820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1074 1075 1.000510 -0.020815 0.001671 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1075 1076 -1.021050 -0.012908 3.104570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1076 1077 1.042460 -0.001380 -0.021989 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1077 1078 1.000320 0.028654 -0.004091 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1078 1079 1.016540 -0.004008 -0.014655 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1079 1080 -1.009220 0.013220 3.104935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1080 1081 0.998449 -0.015993 -0.011717 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1081 1082 0.987184 0.047099 -0.023375 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1082 1083 1.005020 0.001204 0.005641 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1083 1084 0.017132 -0.986391 -1.630670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1084 1085 0.994636 -0.051423 0.007016 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1085 1086 1.022660 -0.018906 0.035317 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1086 1087 1.044440 -0.000320 0.010823 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1087 1088 -0.979173 0.006805 3.123420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1088 1089 1.015740 0.019419 -0.008618 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1089 1090 0.984655 0.062479 0.023806 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1090 1091 0.979540 0.023452 0.010324 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1091 1092 -0.990541 0.013650 3.134355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1092 1093 0.974107 0.010266 0.036205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1093 1094 1.049750 -0.003664 0.032177 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1094 1095 0.995265 -0.005797 0.011751 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1095 1096 -0.996664 -0.013451 -3.132255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1096 1097 0.928559 -0.008583 -0.018201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1097 1098 0.980898 -0.013911 -0.002881 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1098 1099 1.003360 -0.001140 -0.004611 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1099 1100 0.000388 -1.022850 -1.490400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1100 1101 1.011520 0.062454 0.049592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1101 1102 1.031280 -0.009827 -0.021242 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1102 1103 0.979061 0.006857 0.005097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 1104 -0.002786 -1.048110 -1.619960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1104 1105 1.032210 0.028150 0.004861 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1105 1106 0.985504 0.002617 -0.013023 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1106 1107 1.008920 0.010137 0.009901 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1107 1108 0.021868 -0.953140 -1.640725 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1108 1109 1.013190 -0.003016 0.015201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1109 1110 0.963566 -0.009122 -0.022094 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1110 1111 0.980749 0.028007 -0.058645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1111 1112 -0.046965 0.998927 1.587485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1112 1113 0.998647 0.050206 0.001147 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1113 1114 0.971759 0.016259 0.016647 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1114 1115 0.986426 -0.014056 -0.014725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1115 1116 -0.003133 1.017990 1.548870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1116 1117 1.005440 0.000506 -0.031189 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1117 1118 0.997818 0.022847 0.003016 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1118 1119 1.009660 0.007074 0.010979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1119 1120 -1.034750 0.041926 3.100110 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1120 1121 0.953584 -0.012311 0.037938 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1121 1122 0.957693 0.006129 0.021853 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1122 1123 1.021150 0.027101 0.033359 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1123 1124 -0.023512 -1.024950 -1.581450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1124 1125 0.993878 0.010954 0.006675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1125 1126 0.975737 -0.011738 0.009435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1126 1127 1.060710 0.013408 0.026849 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1127 1128 1.005250 -0.045761 -0.014200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1128 1129 1.001480 0.016120 -0.030729 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1129 1130 1.035390 0.000006 0.010239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1130 1131 0.995665 -0.004105 0.032962 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1131 1132 -1.003890 -0.004558 3.108925 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1132 1133 0.987341 0.026664 -0.022166 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1133 1134 1.009270 -0.010944 -0.031648 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1134 1135 1.022550 0.027905 -0.001992 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1135 1136 -0.937087 -0.026520 -3.120235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1136 1137 0.981041 -0.029142 0.002407 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1137 1138 0.991418 0.002140 0.013870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1138 1139 0.985974 0.005203 0.017295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1139 1140 -1.032110 -0.031052 -3.115700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1140 1141 0.979984 -0.005948 -0.043484 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1141 1142 1.019210 0.024729 -0.009777 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1142 1143 1.016690 -0.005843 -0.018359 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1143 1144 -1.007200 0.005236 3.115080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1144 1145 0.978286 0.018182 -0.011371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1145 1146 1.042160 -0.009514 -0.029134 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1146 1147 0.994549 -0.035888 0.012883 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1147 1148 -0.001948 0.999185 1.552850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1148 1149 0.980950 -0.044730 -0.010629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1149 1150 1.020040 0.002597 -0.013624 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1150 1151 1.006580 0.039824 0.003653 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1151 1152 0.023704 1.011730 1.521585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1152 1153 1.003750 0.032793 0.042108 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1153 1154 0.977671 0.016802 0.021349 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1154 1155 0.978817 -0.013134 -0.012707 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1155 1156 -0.022796 0.990207 1.597320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1156 1157 1.012630 -0.015689 -0.028393 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1157 1158 0.948356 0.001158 0.044293 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1158 1159 0.982034 0.025611 0.033969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1159 1160 -0.998861 0.019019 3.124500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1160 1161 0.984300 0.020698 0.003805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1161 1162 0.964275 0.008289 0.005230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1162 1163 1.015020 0.014830 -0.003945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1163 1164 0.969237 -0.002624 0.023017 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1164 1165 1.029730 0.007079 0.026809 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1165 1166 0.968063 0.015674 0.050791 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1166 1167 1.036980 -0.045606 -0.019653 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1167 1168 -1.000230 0.030524 -3.140150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1168 1169 0.989771 0.037089 -0.039920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1169 1170 0.996752 0.032619 0.037247 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1170 1171 0.952762 -0.042870 -0.001279 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1171 1172 -0.983345 -0.004009 -3.131705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1172 1173 0.972854 0.001247 0.043151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1173 1174 0.986233 -0.005153 -0.008659 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1174 1175 1.015300 -0.035567 -0.030972 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1175 1176 -0.047994 0.966016 1.595265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1176 1177 1.009500 -0.006545 -0.026273 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1177 1178 1.026880 0.031292 0.019902 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1178 1179 1.032650 0.040008 0.020246 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1179 1180 -0.015463 -1.004370 -1.578205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1180 1181 0.983435 0.012259 0.011721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1181 1182 1.015360 0.011984 -0.030526 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1182 1183 0.969706 0.003147 -0.021858 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1183 1184 -0.971977 0.032665 -3.122250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1184 1185 0.972366 -0.004279 -0.023860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1185 1186 1.078550 -0.011461 -0.020492 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1186 1187 1.017720 0.016913 0.017435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1187 1188 0.028667 1.030350 1.574600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1188 1189 0.998206 0.018375 -0.008099 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1189 1190 1.036120 -0.001509 -0.028688 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1190 1191 0.970824 -0.003530 -0.023525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1191 1192 0.016365 0.987876 1.571950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1192 1193 1.035590 -0.007834 -0.000732 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1193 1194 1.027600 0.001145 0.004260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1194 1195 1.010680 0.015078 0.006241 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1195 1196 -0.958027 -0.039351 3.120945 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1196 1197 0.968675 -0.008191 0.067444 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1197 1198 0.988229 -0.007498 -0.027797 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1198 1199 0.964896 -0.048469 0.012970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1199 1200 0.026977 -0.993768 -1.571000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1200 1201 0.985941 0.031106 -0.005993 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1201 1202 1.016970 -0.041060 0.004690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1202 1203 1.011410 -0.004761 0.025487 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1203 1204 -0.003859 -1.037160 -1.589965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1204 1205 0.983339 -0.001543 0.018860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1205 1206 0.983264 0.023938 0.003550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1206 1207 0.989014 0.004697 -0.039483 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1207 1208 -0.998725 0.005490 -3.135130 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1208 1209 1.026190 0.015324 -0.039969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1209 1210 0.980552 -0.022986 0.041065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1210 1211 1.030910 -0.036836 -0.029963 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1211 1212 -0.999003 -0.035617 -3.139145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1212 1213 0.994331 0.013569 -0.029557 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1213 1214 1.042180 -0.002264 -0.017336 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1214 1215 0.978535 0.012923 0.017722 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1215 1216 -0.023122 -1.018750 -1.564310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1216 1217 1.015850 -0.025471 0.030830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1217 1218 1.017820 -0.024111 0.040174 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1218 1219 1.009340 -0.000786 -0.022925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1219 1220 0.987541 0.041726 0.006415 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1220 1221 0.981730 -0.003377 0.010790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1221 1222 1.012340 0.000163 -0.008246 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1222 1223 0.981558 -0.037447 -0.003723 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1223 1224 0.019821 1.021450 1.582340 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1224 1225 0.985280 -0.015006 0.001992 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1225 1226 1.008070 -0.035717 -0.010655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1226 1227 0.979316 0.001058 -0.028451 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1227 1228 0.005351 -0.967638 -1.564070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1228 1229 1.020410 0.036598 0.004694 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1229 1230 0.990477 -0.003746 -0.009983 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1230 1231 1.049840 0.009740 -0.007836 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1231 1232 0.006625 0.989405 1.534010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1232 1233 0.989102 0.036173 0.036044 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1233 1234 0.987472 -0.012203 0.022146 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1234 1235 1.007640 0.012787 -0.026540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1235 1236 0.973421 -0.009802 -0.035714 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1236 1237 0.979765 0.002553 0.004590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1237 1238 0.969815 -0.029525 -0.012680 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1238 1239 0.967017 0.069294 0.005499 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1239 1240 -1.004420 -0.011574 -3.130250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1240 1241 0.976640 0.012665 0.056861 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1241 1242 1.021220 0.007657 -0.001125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1242 1243 1.031680 -0.001409 0.013822 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1243 1244 -0.027309 -0.985469 -1.559610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1244 1245 0.984654 -0.009268 0.006300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1245 1246 0.980131 -0.003334 -0.020731 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1246 1247 0.991002 0.038779 -0.011123 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1247 1248 -0.008224 -1.040790 -1.625125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1248 1249 0.994066 -0.015269 0.015843 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1249 1250 1.040460 0.004721 -0.019638 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1250 1251 0.984536 0.007309 0.023042 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1251 1252 -1.025620 -0.007512 -3.136650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1252 1253 1.004660 0.005793 -0.017825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1253 1254 0.975288 0.022046 0.009134 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1254 1255 0.983383 -0.002039 0.035641 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1255 1256 -0.046395 -1.008020 -1.565070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1256 1257 1.015720 0.056645 -0.038318 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1257 1258 1.028860 -0.010680 -0.035779 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1258 1259 0.989889 0.029195 0.022572 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1259 1260 -0.020717 0.973317 1.612760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1260 1261 0.992467 -0.024286 -0.044972 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1261 1262 1.020700 -0.020656 -0.005360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1262 1263 0.992303 -0.006569 0.031323 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1263 1264 -1.009850 0.028145 3.103310 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1264 1265 1.004420 -0.012888 0.001185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1265 1266 1.010050 0.014716 0.007437 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1266 1267 1.003840 0.015372 0.021704 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1267 1268 -0.995165 -0.022189 3.117295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1268 1269 1.020650 -0.002387 -0.050750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1269 1270 0.994205 0.003771 -0.003269 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1270 1271 0.962387 0.002274 -0.002286 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1271 1272 0.001592 -1.013770 -1.598720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1272 1273 1.042080 -0.014500 -0.005401 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1273 1274 1.002490 -0.033513 0.014330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1274 1275 0.992732 0.024383 -0.001569 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1275 1276 -0.011957 0.979233 1.547300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1276 1277 1.019450 -0.043588 -0.001216 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1277 1278 0.987590 0.015465 0.002659 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1278 1279 1.011320 -0.010167 0.024169 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1279 1280 -0.039908 1.005220 1.591640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1280 1281 0.999202 -0.010630 0.016374 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1281 1282 1.038760 -0.042884 0.011913 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1282 1283 1.007110 -0.011486 -0.015868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1283 1284 0.046015 1.003230 1.537490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1284 1285 1.016980 -0.018742 -0.007708 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1285 1286 1.015040 0.024289 -0.005769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1286 1287 1.016340 0.043250 -0.006677 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1287 1288 -0.013501 0.979548 1.556425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1288 1289 1.004890 0.000199 0.015148 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1289 1290 0.986816 -0.021576 0.002589 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1290 1291 1.003660 0.045398 0.033669 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1291 1292 -0.993987 -0.012146 3.139000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1292 1293 1.016470 -0.017505 -0.001741 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1293 1294 0.990284 0.009376 -0.022102 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1294 1295 0.991857 -0.006269 0.001764 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1295 1296 -0.009398 -0.998936 -1.563440 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1296 1297 1.005200 0.000518 0.019131 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1297 1298 1.022820 -0.013248 0.001773 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1298 1299 1.004450 0.014522 0.015388 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1299 1300 0.012775 -0.984144 -1.580780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1300 1301 0.947576 0.033246 -0.042632 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1301 1302 1.005260 -0.004915 -0.016497 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1302 1303 1.002280 0.001625 -0.024313 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1303 1304 -1.016980 -0.013945 -3.118615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1304 1305 0.988037 0.003341 0.016710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1305 1306 0.984677 0.041441 0.044356 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1306 1307 0.990384 0.019010 -0.017861 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1307 1308 -0.013104 -0.966744 -1.606000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1308 1309 0.996919 0.069674 0.011347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1309 1310 0.987620 0.028901 0.046004 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1310 1311 1.029420 0.063164 -0.015948 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1311 1312 0.035108 -1.009310 -1.624910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1312 1313 0.978029 -0.025188 -0.020281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1313 1314 0.984232 -0.018086 0.025649 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1314 1315 0.989851 -0.015855 0.068121 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1315 1316 -0.979803 0.042985 3.140480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1316 1317 0.993803 0.010301 -0.012514 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1317 1318 1.026180 0.023539 -0.024146 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1318 1319 0.981608 0.035528 0.040969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1319 1320 -0.049731 1.038100 1.573850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1320 1321 0.993476 -0.009581 -0.005710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1321 1322 1.041100 0.009389 -0.017868 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1322 1323 1.041830 0.017488 0.032570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1323 1324 -1.009500 0.003852 -3.103190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1324 1325 0.951241 -0.002176 -0.025051 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1325 1326 1.021790 -0.008877 0.019423 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1326 1327 1.019340 0.003809 -0.016046 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1327 1328 0.030688 -0.967907 -1.576460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1328 1329 0.993261 -0.033701 -0.000668 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1329 1330 1.001980 -0.006573 -0.009475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1330 1331 1.040300 -0.015143 0.002863 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1331 1332 0.004438 0.995642 1.557620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1332 1333 0.991863 -0.005123 0.012034 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1333 1334 1.003480 0.013770 0.012584 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1334 1335 0.987106 -0.043817 -0.010237 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1335 1336 0.001073 1.023410 1.597150 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1336 1337 1.030270 -0.027570 0.004702 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1337 1338 0.987853 -0.034408 -0.030597 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1338 1339 1.021640 0.051948 0.023155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1339 1340 -1.017270 -0.022497 3.140855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1340 1341 1.006230 -0.000612 0.002256 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1341 1342 1.033440 0.022271 -0.036296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1342 1343 0.975484 -0.014927 0.016217 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1343 1344 -0.020677 1.001400 1.583500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1344 1345 0.995794 0.015589 0.014292 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1345 1346 0.986945 -0.012995 0.005875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1346 1347 1.009590 -0.021559 -0.026240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1347 1348 -0.043411 0.998147 1.567530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1348 1349 1.016420 -0.013346 -0.007200 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1349 1350 1.048500 -0.009541 -0.016536 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1350 1351 0.995383 0.015271 0.036428 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1351 1352 0.000561 -1.003560 -1.567720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1352 1353 0.983075 -0.003561 -0.006866 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1353 1354 0.990409 0.003042 0.006950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1354 1355 1.003190 -0.017097 0.050726 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1355 1356 0.004829 0.948759 1.552510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1356 1357 1.008050 0.006103 -0.017347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1357 1358 0.968066 0.021545 -0.067239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1358 1359 0.990584 0.000987 0.009917 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1359 1360 -0.013480 1.028940 1.566000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1360 1361 1.021880 0.016726 0.027848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1361 1362 0.963309 -0.027615 0.011415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1362 1363 1.000570 -0.007291 0.019634 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1363 1364 -0.008771 -1.011080 -1.557980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1364 1365 0.948623 -0.012780 -0.032765 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1365 1366 0.990198 0.009585 -0.000555 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1366 1367 1.024630 -0.006676 -0.004926 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1367 1368 -0.026658 -1.018060 -1.534480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1368 1369 0.994776 0.030519 -0.017650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1369 1370 1.014880 0.001783 0.000493 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1370 1371 0.963000 0.008112 -0.012460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1371 1372 0.060241 -1.018220 -1.586360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1372 1373 0.996363 0.021727 -0.021497 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1373 1374 0.991617 -0.006790 -0.018877 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1374 1375 1.018230 0.008975 -0.007892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1375 1376 0.037441 -1.039630 -1.582355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1376 1377 1.030330 -0.021877 -0.019439 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1377 1378 0.955760 -0.034781 0.012503 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1378 1379 1.015960 0.033090 0.049176 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1379 1380 -0.983075 -0.004110 3.129855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1380 1381 0.964802 -0.027792 -0.031485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1381 1382 0.985202 -0.011182 -0.016840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1382 1383 1.031990 -0.027124 0.011456 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1383 1384 -0.038687 -1.010140 -1.577790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1384 1385 1.002320 -0.036154 0.010966 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1385 1386 0.971960 0.025033 0.042366 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1386 1387 1.004410 0.004381 -0.003073 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1387 1388 -0.003192 1.001370 1.575440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1388 1389 0.989516 0.008064 -0.006443 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1389 1390 1.010210 0.016654 -0.032005 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1390 1391 0.957199 -0.009505 0.000911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1391 1392 -1.009980 -0.021543 -3.102555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1392 1393 1.029710 -0.012046 0.012495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1393 1394 0.957875 0.003427 0.001869 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1394 1395 0.973835 0.018489 -0.010450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1395 1396 -0.955031 -0.046422 -3.137440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1396 1397 1.007290 -0.022493 0.038852 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1397 1398 0.980453 0.004656 -0.032659 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1398 1399 1.021970 0.011511 -0.003515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1399 1400 -1.003870 0.017078 3.133280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1400 1401 0.948228 0.002977 0.035787 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1401 1402 0.974946 0.012592 -0.004015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1402 1403 1.000800 -0.012112 0.032122 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1403 1404 -0.953617 0.049332 3.132255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1404 1405 0.988796 0.011720 0.035211 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1405 1406 0.981351 0.017804 0.014944 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1406 1407 1.017770 0.020025 -0.004678 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1407 1408 -0.004520 0.971860 1.580290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1408 1409 1.015650 0.011144 -0.026545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1409 1410 1.028500 -0.032952 -0.014302 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1410 1411 1.053390 -0.040917 -0.022180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1411 1412 -0.993406 -0.035584 3.121285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1412 1413 1.028680 -0.020486 0.003151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1413 1414 1.001860 0.023520 0.001633 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1414 1415 0.978709 -0.010311 -0.016577 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1415 1416 -0.013838 -0.983870 -1.599945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1416 1417 0.982531 -0.021927 -0.016326 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1417 1418 1.010330 -0.030124 -0.007230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1418 1419 0.982628 -0.026409 0.005988 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1419 1420 -0.984445 0.002955 -3.101310 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1420 1421 0.994456 0.009118 0.017272 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1421 1422 0.977550 0.005274 0.020909 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1422 1423 1.003200 0.001364 -0.019814 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1423 1424 -0.003861 1.000770 1.531810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1424 1425 1.001040 0.024354 0.019622 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1425 1426 0.981584 -0.002349 -0.019601 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1426 1427 0.982537 0.021726 -0.007241 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1427 1428 0.008449 -0.997785 -1.572690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1428 1429 0.958707 0.002946 0.017404 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1429 1430 0.985873 -0.017291 0.020117 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1430 1431 1.030660 -0.004323 -0.013798 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1431 1432 0.004899 -1.027260 -1.601430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1432 1433 0.981493 0.025855 -0.016689 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1433 1434 1.020370 0.014109 -0.002223 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1434 1435 1.014970 -0.025306 -0.024373 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1435 1436 0.004535 -0.944284 -1.580595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1436 1437 1.018360 -0.000042 0.033757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1437 1438 0.977533 -0.020501 -0.025049 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1438 1439 0.964881 -0.006273 -0.022248 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1439 1440 -0.027530 1.012300 1.579535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1440 1441 1.017090 0.004831 0.004140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1441 1442 0.996494 -0.014058 0.017436 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1442 1443 0.961168 0.004693 -0.039512 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1443 1444 0.047287 1.018750 1.582510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1444 1445 0.979826 0.008648 -0.006968 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1445 1446 1.010490 -0.012515 0.012555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1446 1447 0.994038 -0.000773 0.031743 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1447 1448 -0.963683 0.008799 3.136440 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1448 1449 1.002140 -0.013533 -0.023682 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1449 1450 1.019880 0.028866 0.023352 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1450 1451 1.024390 -0.011836 0.007301 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1451 1452 1.007350 0.016495 -0.026317 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1452 1453 1.017450 0.001773 -0.034064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1453 1454 0.981097 -0.003543 -0.005681 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1454 1455 1.006880 0.009365 0.025439 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1455 1456 -0.041951 -1.033590 -1.579130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1456 1457 1.002390 -0.007469 -0.006415 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1457 1458 0.964275 0.012199 -0.016396 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1458 1459 0.983656 -0.011549 0.013537 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1459 1460 -0.013641 0.984744 1.624610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1460 1461 1.036060 -0.011236 -0.053872 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1461 1462 1.023570 -0.013343 -0.000876 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1462 1463 1.022040 -0.018247 -0.027939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1463 1464 -0.013518 -1.007350 -1.578640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1464 1465 0.990615 0.026093 -0.000983 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1465 1466 0.967833 0.012969 0.002310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1466 1467 0.991001 0.022606 0.014927 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1467 1468 -0.033745 0.932076 1.560400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1468 1469 0.998997 -0.046303 -0.012433 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1469 1470 1.003720 0.038006 -0.003091 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1470 1471 0.984733 -0.015195 -0.035554 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1471 1472 0.009358 -0.962591 -1.589040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1472 1473 1.007760 0.001143 0.034513 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1473 1474 0.977403 -0.028016 0.017166 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1474 1475 1.000680 0.016118 0.009542 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1475 1476 -0.970623 -0.002361 -3.136480 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1476 1477 1.005020 0.018907 -0.039516 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1477 1478 1.016940 0.007230 0.017688 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1478 1479 0.999150 0.011673 -0.017412 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1479 1480 -0.013306 1.014900 1.610090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1480 1481 0.992240 0.008823 -0.025360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1481 1482 0.982501 -0.025613 -0.049794 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1482 1483 1.008360 -0.008256 0.017522 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1483 1484 0.004330 0.992158 1.576230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1484 1485 0.982446 -0.035905 0.019592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1485 1486 0.992756 -0.005239 -0.007980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1486 1487 1.035630 -0.035510 0.008229 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1487 1488 -0.008640 -1.023380 -1.533520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1488 1489 1.023660 -0.000898 -0.005164 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1489 1490 0.979739 0.003116 0.012889 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1490 1491 0.974236 -0.002847 -0.025071 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1491 1492 -0.044432 1.008460 1.537350 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1492 1493 1.029640 -0.005769 -0.000433 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1493 1494 0.998992 -0.032157 -0.006808 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1494 1495 1.004070 0.019825 -0.022305 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1495 1496 0.034683 -0.990539 -1.576000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1496 1497 0.980598 -0.020439 -0.002863 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1497 1498 0.986133 0.023707 -0.003128 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1498 1499 1.024420 -0.001179 -0.008989 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1499 1500 -0.038681 0.950642 1.568990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1500 1501 1.017110 0.012400 -0.041020 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1501 1502 0.968953 0.021069 -0.000064 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1502 1503 0.981147 -0.032644 0.036178 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1503 1504 -0.989920 -0.008611 3.127065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1504 1505 0.991806 0.010290 0.030954 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1505 1506 1.038220 0.020040 -0.049302 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1506 1507 1.044840 -0.030657 0.029833 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1507 1508 -0.978349 0.002028 -3.128375 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1508 1509 0.983788 0.002684 0.046323 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1509 1510 1.017460 -0.007410 -0.001865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1510 1511 1.029410 -0.008501 -0.000416 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1511 1512 -1.004180 0.035673 -3.122470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1512 1513 1.003390 0.011339 -0.002677 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1513 1514 1.005440 -0.017906 0.023397 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1514 1515 1.004160 -0.015867 0.003998 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1515 1516 0.021257 0.953973 1.583530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1516 1517 1.007890 -0.005422 -0.012391 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1517 1518 0.962996 -0.027640 0.003327 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1518 1519 0.990419 0.005229 0.004724 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1519 1520 -1.008730 -0.015866 -3.130695 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1520 1521 1.025330 -0.014998 0.016679 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1521 1522 1.074830 0.024874 -0.034910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1522 1523 0.976156 -0.025147 -0.031305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1523 1524 0.001428 -1.005290 -1.510400 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1524 1525 0.984426 0.020850 0.002265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1525 1526 1.006840 0.013677 0.001262 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1526 1527 0.994404 -0.005124 -0.003537 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1527 1528 -1.036270 -0.014836 -3.117710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1528 1529 1.015450 -0.001209 -0.034097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1529 1530 1.012050 -0.014517 -0.004497 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1530 1531 1.010820 0.028896 0.000361 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1531 1532 -0.974704 0.039935 -3.109675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1532 1533 1.030910 0.029047 0.010805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1533 1534 1.011560 -0.021934 0.038029 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1534 1535 0.997734 -0.010520 -0.002585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1535 1536 -0.056470 -0.989155 -1.611960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1536 1537 1.004430 0.009485 -0.040028 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1537 1538 1.007080 0.042969 -0.033001 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1538 1539 1.012570 -0.011900 -0.009373 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1539 1540 -0.985286 -0.014881 3.135830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1540 1541 1.013600 -0.007309 0.003790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1541 1542 0.995628 -0.005780 -0.041698 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1542 1543 0.999192 0.016088 -0.025838 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1543 1544 -1.017290 -0.014581 3.123305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1544 1545 0.982481 0.023421 -0.028975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1545 1546 0.999431 -0.003669 -0.015188 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1546 1547 0.998763 0.045269 -0.023062 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1547 1548 -1.001410 0.006477 -3.109675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1548 1549 0.992004 0.024739 0.006493 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1549 1550 1.007840 -0.019298 -0.010758 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1550 1551 0.977769 -0.019129 0.044829 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1551 1552 -0.007233 1.010460 1.565015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1552 1553 0.975610 -0.003070 -0.030036 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1553 1554 1.054900 -0.009195 0.014356 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1554 1555 1.001620 -0.003338 -0.044811 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1555 1556 0.047144 -1.021550 -1.554935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1556 1557 0.990535 -0.010480 -0.026805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1557 1558 0.954123 -0.016601 0.031938 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1558 1559 0.980786 -0.018831 -0.000436 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1559 1560 -0.980744 -0.003011 -3.138220 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1560 1561 0.968235 -0.039988 0.003033 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1561 1562 1.030410 0.021793 -0.018762 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1562 1563 0.996621 0.028377 0.002941 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1563 1564 -0.011874 -0.967631 -1.556900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1564 1565 0.996068 -0.020715 -0.019307 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1565 1566 1.010030 -0.012148 0.011642 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1566 1567 1.007930 -0.006101 -0.006733 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1567 1568 0.009093 1.061550 1.590470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1568 1569 1.011250 0.007961 -0.009759 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1569 1570 1.006870 -0.055088 0.027171 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1570 1571 1.037410 0.020233 -0.010279 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1571 1572 -0.930369 -0.006105 -3.124255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1572 1573 0.986586 -0.025545 0.011224 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1573 1574 0.986377 0.005645 0.011853 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1574 1575 0.999273 -0.000295 0.018382 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1575 1576 -0.033154 -0.979764 -1.586240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1576 1577 0.986718 -0.017490 -0.002412 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1577 1578 1.017860 -0.000942 -0.016183 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1578 1579 0.979914 0.010159 -0.011553 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1579 1580 0.042555 0.995086 1.580570 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1580 1581 0.962798 0.023137 -0.029629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1581 1582 1.010090 0.036780 0.003585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1582 1583 1.008460 0.052117 0.000962 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1583 1584 0.006563 0.976710 1.555795 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1584 1585 0.977982 -0.024269 0.017667 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1585 1586 0.968510 0.018876 -0.036592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1586 1587 1.016770 -0.021714 -0.006241 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1587 1588 -0.004758 -0.919520 -1.557795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1588 1589 1.021940 -0.004654 -0.005840 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1589 1590 1.013410 0.006089 -0.031564 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1590 1591 0.996754 0.011503 0.006309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1591 1592 0.023880 1.016320 1.535165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1592 1593 0.984254 -0.006808 0.018952 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1593 1594 1.010220 -0.014410 0.006700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1594 1595 0.990495 0.022572 0.005650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1595 1596 -0.042333 0.982218 1.587140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1596 1597 1.037160 0.019536 -0.004470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1597 1598 1.006320 -0.018464 -0.000449 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1598 1599 1.056300 -0.009781 0.017202 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1599 1600 -0.029975 1.010220 1.569950 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1600 1601 1.017130 -0.012479 -0.010984 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1601 1602 1.011220 0.014216 0.036876 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1602 1603 0.999048 0.013131 -0.005650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1603 1604 0.001569 0.995845 1.559950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1604 1605 1.056620 0.031770 0.002259 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1605 1606 0.974195 -0.001392 0.009886 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1606 1607 1.000190 0.055441 0.020426 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1607 1608 0.005065 1.008730 1.563805 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1608 1609 1.008850 -0.022244 -0.016913 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1609 1610 0.994171 -0.042701 -0.001324 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1610 1611 0.981118 0.006502 0.020987 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1611 1612 -1.012450 -0.000818 -3.125655 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1612 1613 1.045370 -0.012226 0.017703 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1613 1614 1.000740 0.015016 0.059300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1614 1615 0.975453 0.008173 -0.021324 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1615 1616 0.001770 -1.056990 -1.601070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1616 1617 1.009850 0.026620 0.006169 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1617 1618 0.984002 0.041809 0.005493 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1618 1619 1.031250 -0.030722 0.000113 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 1620 -1.002870 0.008739 3.117630 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1620 1621 1.002130 -0.024203 -0.010587 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1621 1622 0.984657 0.005815 -0.008429 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1622 1623 0.982604 0.002611 -0.023561 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1623 1624 0.001631 -1.016900 -1.575520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1624 1625 0.967685 -0.007268 0.016694 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1625 1626 1.011680 0.018857 0.018174 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1626 1627 1.010590 -0.007930 0.000138 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1627 1628 0.002061 -1.011320 -1.562030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1628 1629 1.018320 0.014726 -0.014454 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1629 1630 0.995268 -0.020465 -0.011650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1630 1631 1.062170 0.001774 0.035292 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1631 1632 -0.000578 -0.999908 -1.557910 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1632 1633 1.015080 -0.010284 -0.004799 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1633 1634 1.017120 -0.007332 0.000732 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1634 1635 0.956753 0.027898 0.013279 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1635 1636 -0.982103 -0.032313 3.116210 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1636 1637 0.974985 -0.012898 0.032699 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1637 1638 0.947081 -0.016836 0.010076 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1638 1639 0.995909 -0.035130 -0.003239 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1639 1640 0.003865 0.986515 1.533620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1640 1641 1.000750 -0.034008 0.039869 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1641 1642 0.994679 0.021656 0.007800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1642 1643 1.028970 -0.011593 -0.037347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1643 1644 0.014573 1.050650 1.544795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1644 1645 1.011010 0.024118 0.002432 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1645 1646 0.970294 -0.027190 0.022424 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1646 1647 0.979149 0.024695 0.003687 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1647 1648 -0.007660 1.018980 1.568790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1648 1649 0.983018 -0.010593 -0.003561 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1649 1650 0.942341 -0.010755 0.006260 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1650 1651 0.994700 0.033144 0.012952 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1651 1652 0.017902 -0.983445 -1.543830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1652 1653 0.971490 -0.010593 -0.015210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1653 1654 1.003090 0.013129 0.011978 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1654 1655 0.991054 0.009127 -0.010044 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1655 1656 0.016157 0.995881 1.573460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1656 1657 1.001420 -0.014689 -0.007877 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1657 1658 1.009400 -0.011638 0.004538 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1658 1659 0.981706 -0.030364 -0.001852 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1659 1660 1.007910 -0.005825 -0.001509 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1660 1661 0.997556 0.029960 -0.003382 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1661 1662 0.961442 -0.010992 -0.018560 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1662 1663 1.010460 0.024943 0.052716 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1663 1664 0.014451 -0.985931 -1.600170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1664 1665 1.022180 -0.007839 0.006995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1665 1666 1.010350 -0.025080 0.038620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1666 1667 0.995971 -0.001193 -0.012324 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1667 1668 -1.022660 0.028506 -3.124105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1668 1669 1.003590 -0.023924 0.006115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1669 1670 0.992949 -0.010496 -0.026128 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1670 1671 0.994560 0.033397 0.010878 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1671 1672 -0.038966 1.008840 1.543710 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1672 1673 0.976257 0.008825 0.024654 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1673 1674 0.995977 -0.017957 0.059325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1674 1675 0.999946 0.012091 0.000364 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1675 1676 0.041092 -0.999682 -1.553650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1676 1677 0.938244 -0.000490 -0.014207 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1677 1678 1.051710 0.000698 -0.006636 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1678 1679 0.972268 -0.028710 0.010802 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1679 1680 -0.032146 0.979130 1.626710 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1680 1681 0.992889 0.012387 0.052047 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1681 1682 1.016490 -0.009785 0.013482 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1682 1683 0.988877 0.009833 -0.002208 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1683 1684 -0.019090 1.016480 1.548825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1684 1685 0.982982 0.004125 -0.005790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1685 1686 1.005920 0.012335 0.004813 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1686 1687 0.974653 -0.041624 -0.011208 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1687 1688 -0.002995 -1.016640 -1.541025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1688 1689 0.983727 0.046453 0.054820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1689 1690 1.001770 0.024936 -0.014972 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1690 1691 1.003880 -0.007180 -0.048969 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1691 1692 0.003239 0.995087 1.564695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1692 1693 0.982345 -0.019461 -0.030104 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1693 1694 0.988540 0.025591 -0.027476 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1694 1695 0.992746 0.013168 0.017529 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1695 1696 -0.049447 -1.010340 -1.579575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1696 1697 1.016660 -0.005417 0.003575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1697 1698 0.971966 -0.010679 0.032479 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1698 1699 0.987217 -0.001098 0.010544 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1699 1700 1.019480 0.009561 0.011592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1700 1701 0.995452 -0.046214 0.016325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1701 1702 1.021080 0.021119 0.004876 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1702 1703 0.973328 -0.004029 -0.000175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1703 1704 -0.015273 1.038180 1.552945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1704 1705 1.015840 -0.055772 0.013991 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1705 1706 0.992684 0.004210 -0.027534 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1706 1707 0.993053 -0.004884 0.006653 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1707 1708 -1.018650 0.009103 3.103660 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1708 1709 0.978209 -0.029946 -0.024923 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1709 1710 1.002470 0.042989 0.026843 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1710 1711 1.005910 0.014421 0.036589 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1711 1712 0.975055 0.005045 -0.019963 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1712 1713 1.010940 -0.022719 -0.029008 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1713 1714 0.982129 0.025079 -0.009193 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1714 1715 0.999992 0.018932 0.016257 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1715 1716 -0.024141 -0.947419 -1.560820 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1716 1717 1.022070 -0.013028 -0.012129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1717 1718 1.002630 -0.042007 0.000516 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1718 1719 0.995103 -0.011417 0.002488 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1719 1720 -0.986584 -0.003785 3.134710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1720 1721 0.999703 -0.007211 0.020092 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1721 1722 1.012740 0.021078 0.001520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1722 1723 1.006700 0.003548 -0.013938 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1723 1724 -0.023818 -0.983498 -1.559580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1724 1725 1.025280 -0.015731 -0.051361 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1725 1726 1.039110 0.029595 -0.016707 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1726 1727 1.032760 0.016480 -0.010120 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1727 1728 -0.041613 -1.004240 -1.540500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1728 1729 0.977472 -0.007653 0.002009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1729 1730 0.985860 -0.013407 -0.031226 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1730 1731 1.011770 -0.036761 -0.029600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1731 1732 -0.975468 0.003389 3.141160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1732 1733 0.980827 0.057743 -0.024448 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1733 1734 1.013700 0.038218 -0.008952 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1734 1735 0.979555 -0.010377 -0.014217 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1735 1736 -0.024428 1.004820 1.552375 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1736 1737 1.036660 0.028552 0.010431 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1737 1738 1.027510 0.003206 -0.024803 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1738 1739 1.014860 -0.009493 0.037046 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1739 1740 1.002220 -0.002544 -0.019702 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1740 1741 0.964259 -0.002777 -0.047754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1741 1742 1.018490 -0.019079 0.014369 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1742 1743 0.967421 -0.044353 -0.027218 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1743 1744 0.009139 -1.000570 -1.581765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1744 1745 0.999631 -0.028653 -0.025390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1745 1746 0.941822 0.016927 -0.000335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1746 1747 0.973019 0.024674 -0.010387 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1747 1748 0.978967 0.048412 -0.000097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1748 1749 1.003590 0.031981 -0.011224 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1749 1750 0.996025 0.020760 0.019619 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1750 1751 1.011750 0.016698 0.001287 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1751 1752 0.013910 -0.989052 -1.543850 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1752 1753 0.986670 0.035839 0.008390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1753 1754 0.975632 -0.021363 -0.006377 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1754 1755 0.993338 0.003556 0.006968 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1755 1756 -0.021775 -0.992473 -1.556890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1756 1757 0.995517 0.007761 0.046817 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1757 1758 1.023910 0.002119 0.033996 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1758 1759 0.983247 -0.001412 0.013912 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1759 1760 0.027218 -0.999338 -1.568250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1760 1761 0.965215 0.008711 -0.008739 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1761 1762 1.018780 0.036461 0.031550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1762 1763 0.994133 0.000537 -0.003629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1763 1764 0.001562 0.972227 1.553370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1764 1765 1.003760 0.038340 -0.001124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1765 1766 0.992540 0.011223 0.003783 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1766 1767 0.958831 -0.040146 0.014347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1767 1768 0.019099 -0.978209 -1.560010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1768 1769 0.972542 -0.006816 0.012539 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1769 1770 1.021690 -0.015925 0.020029 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1770 1771 1.018970 -0.032978 0.005450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1771 1772 -0.971108 -0.032772 -3.120285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1772 1773 0.992219 -0.010425 0.001635 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1773 1774 1.000360 0.008063 -0.018810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1774 1775 1.030470 -0.005846 0.018222 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1775 1776 0.056940 -0.999835 -1.589300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1776 1777 0.952765 -0.064164 0.008750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1777 1778 1.022310 0.005763 0.018765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1778 1779 1.020890 0.011783 -0.054553 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1779 1780 0.004131 0.963550 1.561540 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1780 1781 0.957538 -0.005472 -0.032015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1781 1782 0.961750 0.019297 0.038997 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1782 1783 0.971965 0.021710 0.037501 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1783 1784 0.026461 -1.009080 -1.593940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1784 1785 0.961514 0.026669 0.024436 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1785 1786 0.969123 -0.022763 0.028685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1786 1787 1.054740 -0.001293 -0.020607 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1787 1788 0.002906 1.000750 1.566190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1788 1789 0.989949 0.030519 0.057972 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1789 1790 0.978811 -0.016695 0.018966 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1790 1791 0.999211 -0.024870 -0.022953 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1791 1792 -0.991450 0.013199 -3.120670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1792 1793 1.013680 -0.009616 -0.007036 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1793 1794 1.020690 -0.007120 0.018387 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1794 1795 0.988451 -0.041932 0.015740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1795 1796 -0.992272 -0.003356 3.124690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1796 1797 1.015210 -0.025659 -0.027666 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1797 1798 0.993933 0.005799 -0.006920 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1798 1799 0.983679 -0.004110 0.050145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1799 1800 -0.024830 0.975395 1.568570 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1800 1801 1.017240 -0.026203 0.030944 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1801 1802 0.989772 0.002603 -0.019070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1802 1803 0.979138 0.007411 0.036667 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1803 1804 0.039484 0.994646 1.570195 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1804 1805 1.020490 0.007235 0.001724 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1805 1806 1.013020 0.016633 0.014477 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1806 1807 0.981497 0.008408 -0.034208 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1807 1808 0.003716 -0.986025 -1.591725 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1808 1809 1.022180 0.018680 -0.000087 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1809 1810 1.000740 -0.002997 0.022870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1810 1811 0.996342 -0.013393 0.003990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1811 1812 1.019160 0.018552 0.038285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1812 1813 1.019160 0.023153 -0.006911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1813 1814 0.969921 0.000494 0.043455 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1814 1815 1.042410 -0.005742 -0.003647 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1815 1816 -0.000942 -0.985089 -1.565760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1816 1817 0.951129 -0.000482 -0.026875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1817 1818 1.015340 -0.009014 -0.028702 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1818 1819 0.994177 0.002920 0.022147 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1819 1820 -0.993884 0.005270 -3.122530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1820 1821 1.018980 -0.025608 0.053095 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1821 1822 0.954541 0.008470 -0.020504 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1822 1823 1.005450 -0.043286 -0.015152 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1823 1824 -0.004426 -1.027350 -1.573925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1824 1825 0.988441 0.022422 -0.007960 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1825 1826 1.002530 0.002413 -0.026731 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1826 1827 1.017720 -0.018900 0.004844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1827 1828 -0.989965 -0.004048 -3.133180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1828 1829 1.008210 0.008764 0.005043 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1829 1830 1.014000 0.027351 -0.008361 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1830 1831 1.000500 -0.019047 0.006697 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1831 1832 -0.005468 1.020750 1.564420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1832 1833 1.010900 0.030364 0.036804 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1833 1834 0.977782 0.017499 -0.020604 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1834 1835 1.019230 -0.020166 0.009823 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1835 1836 -0.000109 0.965589 1.548380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1836 1837 1.050560 -0.006795 0.042983 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1837 1838 0.989980 0.013143 0.014904 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1838 1839 0.967221 -0.001408 0.033770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1839 1840 -0.031984 0.949347 1.558835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1840 1841 1.020570 0.006895 0.022962 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1841 1842 0.979065 0.021748 -0.048391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1842 1843 0.962561 0.030637 -0.040107 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1843 1844 1.040730 0.015841 -0.006035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1844 1845 1.005720 -0.009102 0.018583 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1845 1846 0.991756 0.008111 0.037959 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1846 1847 0.971311 0.003796 -0.000634 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1847 1848 -0.012302 -0.959548 -1.557915 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1848 1849 0.982197 -0.006409 0.004008 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1849 1850 1.005470 0.012332 0.012493 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1850 1851 0.983517 0.007817 -0.001608 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1851 1852 -0.015410 1.008950 1.580295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1852 1853 0.991010 -0.012132 0.010098 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1853 1854 1.009470 -0.014518 0.012159 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1854 1855 1.004860 0.008045 0.020854 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1855 1856 -0.011021 -0.971943 -1.574995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1856 1857 1.012640 0.010363 0.007459 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1857 1858 0.964445 0.011772 0.048832 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1858 1859 0.975092 -0.013957 -0.010838 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1859 1860 -0.977867 0.027029 3.122515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1860 1861 1.041070 0.032575 -0.017327 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1861 1862 0.995103 -0.003864 0.020542 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1862 1863 1.023810 0.031081 0.012156 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1863 1864 -0.031269 0.991941 1.600940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1864 1865 1.010430 -0.022713 -0.015713 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1865 1866 0.961861 -0.023818 0.019520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1866 1867 0.995316 -0.034185 0.010784 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1867 1868 0.018653 1.052330 1.580480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1868 1869 0.971838 0.001451 0.018604 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1869 1870 1.006330 -0.013311 -0.000430 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1870 1871 1.012280 -0.005593 -0.016002 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1871 1872 0.010825 -0.980461 -1.585250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1872 1873 0.975423 0.003730 0.003773 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1873 1874 0.961301 -0.034868 0.024896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1874 1875 1.022180 0.005440 0.025695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1875 1876 0.013706 0.987050 1.554840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1876 1877 1.010360 -0.010268 0.012627 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1877 1878 1.003260 -0.005112 -0.030715 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1878 1879 0.940250 -0.037432 0.008295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1879 1880 -0.021389 0.988447 1.584455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1880 1881 1.018190 -0.004343 -0.007612 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1881 1882 0.974757 -0.044462 0.029013 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1882 1883 1.033790 0.011501 -0.004476 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1883 1884 -1.048460 -0.034484 3.117670 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1884 1885 1.013850 0.016637 -0.008829 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1885 1886 1.009910 0.021475 -0.004204 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1886 1887 1.007150 0.016675 0.017413 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1887 1888 0.009653 0.990512 1.550230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1888 1889 1.048430 -0.008036 -0.003808 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1889 1890 0.972008 -0.063256 0.000016 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1890 1891 1.040260 -0.016407 0.002369 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1891 1892 0.018421 -1.001720 -1.572740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1892 1893 1.011270 0.022831 0.024316 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1893 1894 1.004990 -0.012281 0.031249 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1894 1895 0.998691 -0.049117 -0.012611 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1895 1896 -0.013282 -0.997564 -1.551470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1896 1897 0.946457 -0.029009 0.024176 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1897 1898 0.994255 0.030064 0.004082 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1898 1899 1.031700 -0.026189 -0.046416 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1899 1900 -1.051200 -0.018969 -3.122675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1900 1901 0.968351 0.025239 -0.024038 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1901 1902 1.015020 -0.005390 0.018922 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1902 1903 1.027150 -0.025621 0.003509 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1903 1904 0.013783 -1.001070 -1.550220 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1904 1905 0.991977 0.002636 -0.015745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1905 1906 0.970135 -0.014302 0.004993 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1906 1907 1.011100 -0.005782 0.002278 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1907 1908 0.023789 1.065030 1.562050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1908 1909 0.985849 -0.018981 -0.019462 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1909 1910 1.040330 0.039629 -0.017886 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1910 1911 0.969525 -0.006903 -0.000651 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1911 1912 -0.030946 1.001070 1.581315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1912 1913 1.006680 -0.003869 -0.009885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1913 1914 1.012320 -0.008238 -0.030229 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1914 1915 0.981227 0.003851 -0.011130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1915 1916 -0.015771 1.008660 1.591250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1916 1917 0.995758 -0.005949 0.022619 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1917 1918 1.009090 -0.034097 0.000631 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1918 1919 0.997316 -0.040255 -0.020694 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1919 1920 0.021714 -1.043370 -1.578000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1920 1921 1.016470 -0.009130 0.012810 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1921 1922 0.997911 0.029678 0.006309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1922 1923 0.967911 0.034560 -0.034738 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1923 1924 -0.004873 0.991019 1.524600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1924 1925 1.017470 0.010660 -0.008675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1925 1926 0.984683 -0.059702 0.037824 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1926 1927 0.964688 0.016487 0.014714 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1927 1928 -0.023318 -1.003450 -1.583070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1928 1929 1.026350 -0.033868 0.015223 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1929 1930 1.050260 0.010754 -0.026477 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1930 1931 0.961452 0.037439 -0.005010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1931 1932 0.019849 -0.997366 -1.601185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1932 1933 1.019590 0.039934 0.023445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1933 1934 1.028170 -0.005051 -0.030816 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1934 1935 1.008830 0.067951 0.040036 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1935 1936 -0.995970 -0.019982 -3.123890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1936 1937 0.987172 0.032078 0.017019 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1937 1938 1.038230 0.014006 -0.012148 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1938 1939 0.988626 -0.032983 -0.004386 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1939 1940 1.016620 -0.029160 0.014786 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1940 1941 0.982077 0.007146 0.012077 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1941 1942 1.001440 0.015425 -0.026169 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1942 1943 0.983561 0.018599 -0.010609 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1943 1944 0.985794 0.027860 0.028658 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1944 1945 1.018290 0.006961 0.035231 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1945 1946 0.982856 -0.009942 -0.006378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1946 1947 1.000690 0.004596 -0.040337 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1947 1948 -0.003779 1.050160 1.591410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1948 1949 0.988862 -0.003627 0.009649 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1949 1950 1.006900 -0.016227 0.006278 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1950 1951 1.007820 -0.010573 0.019185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1951 1952 0.025756 -0.987220 -1.573540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1952 1953 0.949943 -0.004763 0.031151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1953 1954 0.998962 -0.028612 0.024256 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1954 1955 1.050640 -0.056139 0.022625 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1955 1956 0.038517 0.963756 1.596140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1956 1957 0.938361 0.026511 -0.003393 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1957 1958 0.997767 0.047833 -0.001885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1958 1959 0.995216 -0.017076 0.042314 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1959 1960 0.016038 1.002660 1.600300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1960 1961 1.051010 0.031449 -0.026645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1961 1962 1.003100 -0.020270 0.005235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1962 1963 0.978209 -0.031376 -0.002672 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1963 1964 -1.003280 0.019054 -3.085870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1964 1965 0.978539 0.020003 -0.018549 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1965 1966 1.020270 0.033554 0.011684 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1966 1967 0.990613 -0.005521 -0.005459 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1967 1968 -0.014273 -0.964791 -1.595990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1968 1969 1.005750 -0.016200 0.002282 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1969 1970 1.011880 -0.001514 0.008597 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1970 1971 0.996474 -0.039021 -0.004009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1971 1972 -0.965259 0.022969 3.105490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1972 1973 1.021340 -0.025372 -0.030486 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1973 1974 0.989554 -0.024904 0.001612 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1974 1975 0.997283 0.008209 0.002068 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1975 1976 0.015782 0.997843 1.538100 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1976 1977 0.996526 0.027942 -0.044433 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1977 1978 1.022830 -0.015197 -0.002296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1978 1979 1.009760 0.025564 0.004839 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1979 1980 -0.006370 -1.024710 -1.539460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1980 1981 0.981545 0.002806 -0.025705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1981 1982 1.007710 -0.015773 -0.027848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1982 1983 1.002870 -0.015626 0.018384 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1983 1984 0.009221 -1.011090 -1.570670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1984 1985 1.008430 -0.020619 0.032233 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1985 1986 1.018970 -0.014423 0.030619 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1986 1987 1.011310 -0.021775 -0.018570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1987 1988 1.025120 0.001791 -0.024501 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1988 1989 0.981354 0.016810 -0.020047 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1989 1990 1.016950 -0.014146 -0.025377 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1990 1991 0.971500 -0.024429 0.017854 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1991 1992 -1.020570 0.034192 3.113320 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1992 1993 0.983384 -0.025637 -0.014420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1993 1994 0.987247 -0.010559 0.011574 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1994 1995 1.004440 0.028290 -0.009418 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1995 1996 -0.035746 1.010730 1.601055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1996 1997 1.010580 0.003843 -0.023995 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1997 1998 0.974704 0.013275 -0.027600 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1998 1999 1.030440 0.010950 -0.010245 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1999 2000 0.992546 -0.008772 -0.027574 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2000 2001 0.940349 -0.006631 0.053433 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2001 2002 1.068410 0.007070 0.003591 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2002 2003 1.042480 -0.007161 -0.008503 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2003 2004 -1.008860 -0.034767 3.141080 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2004 2005 1.002220 -0.017538 -0.018939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2005 2006 1.006190 -0.012172 -0.040500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2006 2007 1.014580 0.022707 -0.042583 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2007 2008 -1.015040 -0.016273 3.123515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2008 2009 1.023270 0.001952 0.019396 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2009 2010 0.980896 0.040167 -0.005115 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2010 2011 1.015000 -0.023482 0.001754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2011 2012 -0.981526 -0.020971 -3.126005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2012 2013 0.979661 0.025197 0.037648 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2013 2014 1.008670 -0.000253 0.016174 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2014 2015 0.955407 0.043069 -0.024837 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2015 2016 -0.010939 -1.035910 -1.520250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2016 2017 1.019780 0.013410 0.016826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2017 2018 1.012700 0.014139 0.011761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2018 2019 1.015350 0.038756 -0.017072 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2019 2020 0.029734 -0.943963 -1.579310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2020 2021 0.993207 0.006947 -0.002179 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2021 2022 0.984309 -0.025611 0.001214 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2022 2023 1.041560 0.022534 -0.016101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2023 2024 0.006455 1.005940 1.588220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2024 2025 0.976628 0.010311 0.014145 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2025 2026 1.020090 -0.027414 0.027454 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2026 2027 0.976556 0.041592 -0.027262 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2027 2028 -0.983270 -0.013815 3.120690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2028 2029 0.991677 -0.010706 -0.006050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2029 2030 1.027050 -0.001327 -0.020557 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2030 2031 1.021830 -0.058484 -0.001124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2031 2032 0.012301 -0.995639 -1.594810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2032 2033 1.022900 -0.000438 -0.028488 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2033 2034 0.989433 0.008658 -0.035447 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2034 2035 0.995488 0.048026 -0.005648 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2035 2036 0.019810 1.008250 1.558380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2036 2037 1.029170 -0.021064 -0.003291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2037 2038 0.999018 -0.020791 -0.055608 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2038 2039 0.981758 -0.006766 0.025574 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2039 2040 -1.015480 0.026702 -3.105220 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2040 2041 0.980184 0.023174 -0.004400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2041 2042 0.971523 0.009725 0.036663 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2042 2043 1.007400 -0.026936 -0.041049 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2043 2044 0.003289 -1.012940 -1.554230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2044 2045 1.035850 0.039481 0.013036 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2045 2046 0.933262 -0.034209 -0.016616 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2046 2047 0.998488 0.001196 -0.012684 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2047 2048 -1.009510 0.010345 -3.097565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2048 2049 1.014390 0.016811 -0.026539 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2049 2050 1.005950 0.010759 -0.004190 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2050 2051 0.957288 -0.005589 -0.006968 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2051 2052 -0.006942 -0.985960 -1.601800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2052 2053 1.016960 0.007085 -0.007945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2053 2054 0.964718 -0.066712 0.026315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2054 2055 0.984921 -0.051171 -0.002568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2055 2056 -0.995745 -0.006755 -3.087125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2056 2057 0.970021 -0.000399 -0.011341 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2057 2058 0.994185 -0.011705 -0.025944 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2058 2059 1.024610 0.010342 -0.002397 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2059 2060 -1.000170 0.006062 3.117565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2060 2061 1.016150 0.027556 0.044844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2061 2062 0.956526 -0.014530 -0.021788 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2062 2063 0.998966 0.036014 0.034442 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2063 2064 -0.013323 -0.963384 -1.584120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2064 2065 1.033180 -0.013257 -0.047500 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2065 2066 1.035430 -0.021410 0.016631 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2066 2067 1.007860 0.044759 0.037445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2067 2068 -1.006030 0.010557 -3.137685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2068 2069 0.970979 0.000906 0.018203 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2069 2070 0.950895 0.003764 0.003469 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2070 2071 1.036230 -0.008108 0.046107 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2071 2072 -0.003183 -1.009030 -1.567580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2072 2073 1.014710 0.055274 0.009138 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2073 2074 0.984666 0.014239 -0.018886 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2074 2075 1.025220 -0.013537 0.011820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2075 2076 -0.012463 0.962999 1.593530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2076 2077 0.977926 0.018541 0.017264 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2077 2078 0.983376 0.016227 -0.000692 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2078 2079 0.997229 -0.035087 0.017960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2079 2080 -0.004786 1.032550 1.568040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2080 2081 1.035130 -0.035468 0.031323 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2081 2082 1.016980 -0.007531 0.005597 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2082 2083 0.990182 -0.007600 -0.042809 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2083 2084 -0.946981 0.034552 -3.103000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2084 2085 0.964024 0.001002 -0.047533 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2085 2086 1.025500 0.040295 -0.049497 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2086 2087 0.994768 0.044702 0.056474 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2087 2088 -0.981345 0.030133 3.130940 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2088 2089 1.041920 -0.003790 0.018031 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2089 2090 1.003090 0.033491 -0.005414 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2090 2091 1.018950 0.003695 -0.030217 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2091 2092 -1.040340 -0.003694 3.122305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2092 2093 0.969072 0.008459 -0.020457 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2093 2094 0.987400 -0.007668 0.000434 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2094 2095 1.061040 -0.021750 -0.014378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2095 2096 -0.003128 -1.028580 -1.561510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2096 2097 0.973587 -0.001105 0.019169 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2097 2098 1.024040 -0.001938 0.005528 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2098 2099 1.055990 -0.011525 -0.010125 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2099 2100 1.006990 0.015479 0.015865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2100 2101 1.004150 0.003161 -0.015203 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2101 2102 1.017630 -0.020906 -0.003197 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2102 2103 0.982532 -0.021809 -0.011535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2103 2104 -0.950207 -0.026689 3.125840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2104 2105 1.022850 0.002802 0.016538 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2105 2106 1.031800 0.011439 -0.004279 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2106 2107 0.980936 -0.012748 -0.016849 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2107 2108 -1.022080 0.011772 3.105585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2108 2109 1.013460 -0.022376 0.014260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2109 2110 1.007240 0.012771 -0.000680 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2110 2111 1.005640 -0.011419 0.009690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2111 2112 0.058612 1.000730 1.546690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2112 2113 1.017260 0.023561 0.004502 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2113 2114 1.012340 -0.041780 -0.047730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2114 2115 1.017850 -0.031193 0.023781 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2115 2116 -0.991812 -0.008336 -3.133385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2116 2117 1.004990 0.009494 -0.022151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2117 2118 1.015760 0.023248 0.008926 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2118 2119 0.995019 0.023313 -0.000931 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2119 2120 -0.983702 0.027731 -3.133700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2120 2121 1.016620 0.003319 -0.005155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2121 2122 0.982226 0.049814 0.037364 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2122 2123 1.030120 0.046748 -0.018637 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2123 2124 0.008478 -0.988051 -1.558760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2124 2125 1.016960 -0.006730 0.007794 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2125 2126 1.008270 0.042655 0.011296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2126 2127 1.012220 -0.034362 -0.033593 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2127 2128 0.007788 -0.992941 -1.563885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2128 2129 0.984670 0.012486 0.002274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2129 2130 1.006180 -0.001679 0.046162 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2130 2131 1.026490 -0.008122 -0.001819 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2131 2132 -1.057580 0.018758 -3.136750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2132 2133 1.002110 0.027777 -0.006794 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2133 2134 1.019310 -0.031033 0.027646 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2134 2135 1.026900 0.010415 0.042398 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2135 2136 0.992567 0.022586 -0.025458 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2136 2137 0.931255 0.034897 0.008005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2137 2138 1.047420 0.035540 0.019239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2138 2139 1.023330 0.006495 0.000536 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2139 2140 -0.002248 0.965347 1.581690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2140 2141 1.032770 -0.032427 -0.012871 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2141 2142 1.052630 -0.011374 -0.005072 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2142 2143 1.020480 -0.002243 -0.024892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2143 2144 0.012968 1.013620 1.540950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2144 2145 0.998701 -0.067667 -0.017651 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2145 2146 1.007400 0.007602 -0.004086 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2146 2147 0.974539 0.011677 0.015368 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2147 2148 -0.978161 -0.000110 3.108475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2148 2149 1.024440 0.041808 -0.025449 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2149 2150 0.995337 -0.020572 -0.006939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2150 2151 1.046590 0.005483 0.021843 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2151 2152 0.051857 -0.985933 -1.594980 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2152 2153 1.008630 -0.003048 0.018755 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2153 2154 1.024160 0.025559 0.027610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2154 2155 1.018630 -0.025712 0.019567 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2155 2156 -0.022736 0.993529 1.565530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2156 2157 0.976283 -0.012937 0.007530 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2157 2158 0.988690 0.013286 0.010810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2158 2159 0.991272 -0.002147 -0.011057 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2159 2160 -1.056390 0.003847 3.133990 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2160 2161 1.008260 0.029409 0.020329 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2161 2162 0.993312 -0.014657 0.011706 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2162 2163 0.977908 0.006529 -0.005051 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2163 2164 0.014501 -0.999212 -1.553490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2164 2165 1.015860 -0.040281 0.033981 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2165 2166 1.036540 0.007358 -0.008239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2166 2167 0.994539 -0.020159 0.027378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2167 2168 -1.030390 0.055379 3.121745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2168 2169 1.045960 -0.013315 -0.040480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2169 2170 1.002250 0.049392 0.041404 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2170 2171 1.019940 -0.029276 -0.024227 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2171 2172 0.029003 1.013020 1.538140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2172 2173 1.017150 -0.008493 -0.001111 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2173 2174 0.976563 -0.027183 -0.037255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2174 2175 0.973208 0.002472 0.022230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2175 2176 0.027730 1.030520 1.558410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2176 2177 1.021900 -0.022407 -0.013673 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2177 2178 0.995381 -0.005357 -0.026551 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2178 2179 0.954311 0.026648 -0.003842 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2179 2180 0.011691 0.990744 1.492550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2180 2181 1.026410 -0.017147 -0.011521 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2181 2182 1.003870 0.025273 0.024417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2182 2183 0.988373 0.027187 -0.002765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2183 2184 -1.065960 -0.007610 3.118255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2184 2185 0.986316 0.021172 0.034786 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2185 2186 1.006180 -0.002144 -0.021055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2186 2187 0.968373 -0.004526 0.006409 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2187 2188 -0.012895 0.966498 1.586900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2188 2189 1.045970 -0.019880 -0.027720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2189 2190 0.981791 0.004861 0.007072 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2190 2191 0.995094 -0.012878 0.026023 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2191 2192 -0.961440 -0.021106 -3.133210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2192 2193 1.017660 -0.011176 -0.047200 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2193 2194 0.979011 0.009949 -0.014368 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2194 2195 1.011600 0.003916 0.015697 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2195 2196 -0.980475 -0.001557 -3.136945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2196 2197 0.987952 0.004940 -0.010457 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2197 2198 1.018400 -0.044567 -0.030291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2198 2199 0.953963 -0.005405 0.019963 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2199 2200 -0.021835 1.003330 1.604900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2200 2201 1.001820 0.025053 0.002536 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2201 2202 1.016470 -0.014723 -0.016036 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2202 2203 0.995059 0.002279 0.026542 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2203 2204 -1.068180 0.016054 3.128935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2204 2205 1.020460 -0.007700 0.019517 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2205 2206 1.026970 -0.025728 -0.002765 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2206 2207 1.032480 0.006334 -0.003792 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2207 2208 -0.985657 0.016897 3.124200 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2208 2209 0.972282 -0.080343 0.009407 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2209 2210 0.993269 0.009632 0.003802 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2210 2211 0.977844 -0.005234 -0.003852 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2211 2212 -0.006269 -1.021860 -1.539640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2212 2213 1.010870 -0.000066 0.004162 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2213 2214 0.987253 0.032775 -0.002071 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2214 2215 1.030050 -0.004232 0.011431 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2215 2216 -0.031279 -1.038320 -1.557260 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2216 2217 0.993079 0.002678 0.026039 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2217 2218 0.999888 -0.006301 0.005447 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2218 2219 0.985152 -0.027120 0.026541 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2219 2220 -0.998153 0.003666 3.133030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2220 2221 0.981120 0.001252 -0.021093 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2221 2222 0.996330 -0.015277 -0.034121 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2222 2223 1.016820 0.021726 0.005339 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2223 2224 -0.984286 0.002749 3.094135 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2224 2225 0.957765 0.015462 0.058807 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2225 2226 0.950216 0.000793 0.009652 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2226 2227 0.944046 -0.027346 0.024309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2227 2228 0.963573 -0.006808 0.013987 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2228 2229 0.983392 -0.030768 0.005835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2229 2230 0.966226 -0.013836 -0.044781 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2230 2231 1.000010 0.057204 -0.017219 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2231 2232 -0.053522 1.005850 1.579050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2232 2233 1.012220 0.007449 0.020206 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2233 2234 0.964490 0.004039 0.017231 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2234 2235 1.009480 -0.004538 0.010345 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2235 2236 -0.006583 0.985962 1.560270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2236 2237 0.989409 0.020924 0.019586 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2237 2238 1.022260 0.006167 0.009662 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2238 2239 1.006370 -0.005268 0.037261 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2239 2240 -1.016410 -0.007176 -3.132270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2240 2241 1.002780 -0.022590 0.016870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2241 2242 0.997150 0.011086 0.007229 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2242 2243 1.016960 -0.016305 0.046655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2243 2244 -0.010517 1.044900 1.542950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2244 2245 1.032580 0.006974 -0.019392 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2245 2246 1.013140 0.009063 -0.005110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2246 2247 0.992523 -0.003939 0.012696 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2247 2248 -0.025044 0.989119 1.577340 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2248 2249 0.987705 0.008050 -0.057804 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2249 2250 0.991544 -0.004244 0.024299 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2250 2251 0.975652 -0.008011 0.023866 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2251 2252 -0.972110 0.018963 -3.108520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2252 2253 0.962608 -0.006922 0.015122 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2253 2254 1.031540 -0.023092 -0.005111 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2254 2255 0.987742 -0.011404 -0.011504 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2255 2256 -0.006935 1.003850 1.618330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2256 2257 0.977098 -0.019237 -0.001009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2257 2258 1.011330 -0.024876 -0.032727 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2258 2259 1.004850 0.005802 0.013446 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2259 2260 -0.961796 0.023777 -3.131450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2260 2261 0.994603 0.018297 -0.028798 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2261 2262 1.018200 -0.016423 -0.020742 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2262 2263 0.991634 -0.001844 0.027256 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2263 2264 -1.011840 -0.001321 -3.129395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2264 2265 0.959858 -0.013361 -0.019115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2265 2266 0.986769 -0.028462 -0.010094 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2266 2267 0.982912 0.004495 0.026830 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2267 2268 -0.013295 1.030650 1.538240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2268 2269 0.995845 0.008441 -0.012826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2269 2270 0.979924 -0.003410 -0.015835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2270 2271 1.004120 -0.004020 -0.006003 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2271 2272 -0.999240 0.017395 3.136585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2272 2273 0.964108 -0.015085 -0.011874 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2273 2274 0.992096 -0.009540 0.001329 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2274 2275 1.003220 0.009042 0.004992 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2275 2276 -1.038190 -0.022834 3.138090 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2276 2277 1.006270 -0.022595 0.020943 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2277 2278 0.976669 0.022939 0.040879 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2278 2279 0.955196 0.017362 0.004796 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2279 2280 -0.010561 0.981420 1.560995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2280 2281 0.982852 0.001389 -0.034358 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2281 2282 0.964336 0.029264 -0.007786 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2282 2283 0.999332 0.004466 -0.003232 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2283 2284 -0.005578 -0.976189 -1.557885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2284 2285 1.031070 0.017047 -0.006864 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2285 2286 1.030310 -0.005456 0.046584 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2286 2287 1.011550 -0.000339 0.011878 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2287 2288 -1.016860 0.010566 3.065085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2288 2289 0.987727 -0.003115 0.012480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2289 2290 1.027920 -0.018056 0.011793 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2290 2291 0.965365 0.002939 0.052420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2291 2292 -0.016747 -0.989387 -1.574860 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2292 2293 0.994747 -0.020278 0.007466 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2293 2294 1.021230 0.002379 0.004084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2294 2295 1.002380 0.010172 0.005073 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2295 2296 -0.991975 0.014164 -3.131505 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2296 2297 0.976138 -0.029314 -0.001216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2297 2298 1.011000 0.017132 0.017032 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2298 2299 0.980741 0.029773 -0.016281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2299 2300 -0.030608 0.971841 1.582090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2300 2301 1.016330 -0.005065 -0.020797 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2301 2302 0.985007 0.031850 -0.031743 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2302 2303 1.031060 -0.007925 -0.019002 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2303 2304 -1.000010 0.019526 -3.125330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2304 2305 1.016930 -0.016914 -0.009761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2305 2306 1.066740 0.014414 -0.014081 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2306 2307 0.994896 -0.011799 0.017543 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2307 2308 -0.003200 -1.000080 -1.560900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2308 2309 1.039640 0.020246 -0.023688 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2309 2310 0.967497 0.006823 -0.003835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2310 2311 0.998602 0.008010 0.003722 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2311 2312 -0.988340 0.010259 3.088040 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2312 2313 1.042150 -0.023355 0.018450 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2313 2314 1.020660 -0.023487 -0.013464 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2314 2315 1.023930 0.009704 0.012290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2315 2316 0.005053 -0.983068 -1.564540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2316 2317 0.983196 -0.030728 -0.019655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2317 2318 1.002940 -0.008084 0.025343 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2318 2319 1.008540 0.005913 -0.001855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2319 2320 -0.971417 0.043746 -3.101605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2320 2321 0.962768 -0.027305 -0.021033 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2321 2322 1.021310 0.014178 0.009114 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2322 2323 0.988555 0.013838 0.000278 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2323 2324 0.029702 0.954811 1.552985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2324 2325 0.996893 0.013360 -0.011411 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2325 2326 0.977270 -0.000047 -0.001728 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2326 2327 0.996274 0.009713 -0.009773 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2327 2328 -0.982517 0.007093 -3.117525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2328 2329 0.996778 -0.012108 -0.013632 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2329 2330 1.031550 -0.041662 -0.000858 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2330 2331 1.018110 0.022392 0.010124 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2331 2332 0.017954 -0.973302 -1.561420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2332 2333 1.003410 0.013334 0.020683 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2333 2334 0.999358 0.006391 0.011109 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2334 2335 1.019420 -0.013998 -0.012790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2335 2336 -0.990891 -0.006389 -3.141145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2336 2337 1.047360 0.002590 -0.011342 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2337 2338 0.993049 0.022603 0.016401 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2338 2339 0.984999 0.048005 0.021117 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2339 2340 -1.004790 0.022038 3.105135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2340 2341 0.967929 0.043233 0.015299 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2341 2342 0.979235 -0.013958 -0.032423 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2342 2343 1.010190 0.031600 -0.040917 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2343 2344 -0.001013 0.944312 1.567590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2344 2345 1.011730 0.003711 0.040862 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2345 2346 0.998024 -0.006683 0.016482 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2346 2347 0.965061 0.033705 0.013199 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2347 2348 -0.009474 0.999228 1.571880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2348 2349 1.029660 0.022253 0.019872 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2349 2350 1.026370 -0.011676 -0.023423 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2350 2351 1.010560 -0.001785 -0.003004 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2351 2352 0.009611 -1.001350 -1.550130 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2352 2353 1.003510 -0.033352 -0.013055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2353 2354 0.997950 0.009486 0.005186 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2354 2355 0.979623 -0.024012 0.055905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2355 2356 -1.014560 -0.040374 3.097515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2356 2357 1.005210 0.004018 0.005326 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2357 2358 0.985050 0.002348 0.026816 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2358 2359 0.986437 -0.005395 -0.012540 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2359 2360 -0.008750 1.007640 1.545720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2360 2361 0.998504 -0.049802 0.020907 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2361 2362 1.028520 0.013809 0.021436 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2362 2363 1.010870 0.016496 -0.004580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2363 2364 -0.009091 -1.027940 -1.549010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2364 2365 0.999059 0.012991 0.000282 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2365 2366 0.999890 -0.001832 0.018868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2366 2367 0.981051 0.009825 -0.057127 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2367 2368 -0.959298 -0.003647 -3.138705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2368 2369 1.025310 0.000230 -0.020492 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2369 2370 0.984088 -0.027691 0.010033 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2370 2371 1.013320 0.028717 0.021406 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2371 2372 -0.001713 1.020900 1.564120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2372 2373 0.987343 0.040021 0.004182 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2373 2374 1.016220 -0.011545 -0.026480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2374 2375 0.953847 0.003734 0.018381 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2375 2376 -0.041983 0.996880 1.612355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2376 2377 1.001640 0.018179 -0.021892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2377 2378 1.019150 -0.007505 -0.004849 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2378 2379 1.010050 -0.008334 -0.006384 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2379 2380 -0.019521 0.995057 1.559390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2380 2381 1.019800 -0.017413 0.000084 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2381 2382 0.991347 -0.009080 0.021535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2382 2383 0.990245 -0.030988 0.005047 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2383 2384 0.006249 1.035310 1.530010 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2384 2385 1.018240 0.015360 0.018327 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2385 2386 0.995664 0.007354 -0.017274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2386 2387 1.010370 -0.002864 -0.001315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2387 2388 0.042008 0.978582 1.578830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2388 2389 1.027140 0.001589 0.003003 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2389 2390 1.029630 -0.029960 0.001191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2390 2391 0.993139 -0.014918 0.007289 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2391 2392 -0.005049 -0.999678 -1.574630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2392 2393 1.024990 0.043257 0.034012 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2393 2394 1.035110 -0.011643 0.005800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2394 2395 1.003780 0.000291 -0.003714 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2395 2396 -0.991713 0.005119 3.091115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2396 2397 0.983909 0.005095 -0.028187 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2397 2398 0.988269 0.012374 0.001065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2398 2399 1.043820 0.014037 0.018911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2399 2400 0.007640 0.951301 1.582740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2400 2401 1.007510 -0.019002 0.027393 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2401 2402 0.990493 -0.035273 0.035022 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2402 2403 0.982867 -0.005261 0.010285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2403 2404 0.004757 -1.021510 -1.598940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2404 2405 1.016710 0.032368 0.010579 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2405 2406 1.014130 -0.003454 0.011072 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2406 2407 0.986152 -0.009548 0.038560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2407 2408 0.975126 -0.017190 -0.018636 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2408 2409 0.989405 -0.003177 0.002767 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2409 2410 0.987969 0.003733 -0.018877 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2410 2411 0.978191 0.034119 -0.018791 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2411 2412 0.017579 -0.973635 -1.564995 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2412 2413 1.027290 -0.049605 -0.014309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2413 2414 1.007370 -0.005587 0.008571 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2414 2415 1.004390 0.015882 -0.038891 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2415 2416 -0.007043 -1.001090 -1.550010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2416 2417 0.993548 -0.049697 -0.036580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2417 2418 1.009430 0.002092 0.008475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2418 2419 0.952458 -0.003079 -0.020137 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2419 2420 0.017409 -0.983651 -1.603000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2420 2421 0.998007 -0.004617 0.014964 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2421 2422 0.973989 -0.020616 -0.044290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2422 2423 0.993037 -0.002264 -0.021016 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2423 2424 0.007441 -1.019110 -1.562300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2424 2425 0.997725 0.037861 0.009357 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2425 2426 0.993401 0.001353 0.014099 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2426 2427 0.980140 -0.019804 0.020875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2427 2428 -1.015490 0.028316 3.140010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2428 2429 1.013550 -0.016318 0.019249 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2429 2430 1.000500 0.012007 0.043061 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2430 2431 0.980536 0.028899 -0.037764 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2431 2432 -0.038224 0.989710 1.601390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2432 2433 0.945463 0.033844 0.011078 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2433 2434 1.037410 0.007813 0.030380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2434 2435 1.015130 0.021090 -0.001540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2435 2436 0.021441 -0.952513 -1.507160 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2436 2437 1.007310 0.007148 -0.029958 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2437 2438 0.994819 -0.008296 -0.011083 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2438 2439 0.974810 -0.002067 -0.008788 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2439 2440 -1.017670 -0.015610 -3.131560 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2440 2441 0.973763 -0.075845 -0.002620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2441 2442 1.004860 0.014404 0.002830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2442 2443 1.035850 -0.011818 0.004399 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2443 2444 -0.997898 0.000558 -3.137185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2444 2445 0.985069 0.035172 0.021271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2445 2446 0.987248 -0.041376 0.014914 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2446 2447 0.966632 0.011426 -0.008365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2447 2448 0.015128 1.016740 1.563630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2448 2449 1.039410 0.020530 -0.006167 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2449 2450 1.048360 0.024748 0.058372 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2450 2451 0.975624 0.004843 -0.029735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2451 2452 -0.030815 -0.980627 -1.563160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2452 2453 0.994648 -0.005211 0.041407 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2453 2454 1.012790 0.014637 0.010812 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2454 2455 1.002430 0.001714 0.001856 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2455 2456 -0.009736 -0.945141 -1.603440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2456 2457 0.975689 -0.032321 0.004997 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2457 2458 0.985021 0.001410 0.006613 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2458 2459 0.998864 -0.020136 0.024231 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2459 2460 -1.019980 -0.044906 3.131590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2460 2461 0.976128 0.023313 -0.007632 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2461 2462 1.060540 0.004224 -0.016510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2462 2463 0.985749 -0.009909 0.006406 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2463 2464 -0.011768 -1.037940 -1.556310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2464 2465 1.002600 -0.008214 0.042000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2465 2466 1.010000 0.017268 0.004746 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2466 2467 0.992166 -0.015853 0.005046 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2467 2468 -0.001444 -1.003060 -1.579880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2468 2469 1.024790 0.006704 -0.004062 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2469 2470 1.017810 0.022026 0.028978 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2470 2471 1.006580 0.016374 0.006954 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2471 2472 -1.027070 0.029597 3.127640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2472 2473 0.977193 -0.013784 0.002857 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2473 2474 0.984869 -0.025309 0.043296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2474 2475 0.976183 0.021947 -0.033032 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2475 2476 -0.027204 -1.005580 -1.596570 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2476 2477 0.971386 0.021212 -0.005019 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2477 2478 1.000340 0.031375 -0.010893 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2478 2479 0.991888 -0.033196 0.024249 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2479 2480 0.019540 1.003840 1.564780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2480 2481 1.016820 0.005368 0.002982 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2481 2482 1.018170 0.020080 0.003591 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2482 2483 1.006980 -0.002176 0.009353 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2483 2484 -1.011410 0.022933 -3.131930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2484 2485 1.008570 0.036605 -0.004531 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2485 2486 0.978324 0.008132 -0.031925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2486 2487 0.983592 -0.000733 0.014368 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2487 2488 -1.024440 -0.006391 -3.139065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2488 2489 1.031550 0.038049 -0.013959 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2489 2490 0.971965 -0.009160 -0.019244 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2490 2491 0.971884 -0.043031 0.041564 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2491 2492 -0.993596 -0.026781 -3.112950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2492 2493 1.025120 0.009166 0.000986 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2493 2494 1.021710 0.012302 0.011876 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2494 2495 0.982030 -0.037073 -0.010094 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2495 2496 -0.031874 0.987954 1.566030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2496 2497 0.996470 -0.008052 0.030842 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2497 2498 0.985049 -0.014365 0.006652 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2498 2499 0.950240 0.015325 0.009112 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2499 2500 0.023296 0.952911 1.552950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2500 2501 0.972448 -0.008243 -0.019995 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2501 2502 1.017900 0.026273 0.039442 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2502 2503 0.996636 0.015367 -0.031503 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2503 2504 0.003166 -0.974354 -1.570430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2504 2505 0.997176 0.014390 -0.031265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2505 2506 0.958666 0.001057 0.013308 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2506 2507 0.983484 -0.035570 -0.012554 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2507 2508 -0.000170 1.015400 1.558610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2508 2509 0.992670 0.007838 0.040711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2509 2510 1.005290 0.014293 0.028766 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2510 2511 0.992335 0.034436 -0.000834 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2511 2512 0.010893 -0.999550 -1.592650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2512 2513 0.956889 0.024955 -0.005332 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2513 2514 1.029510 0.003366 -0.025460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2514 2515 0.974999 0.036194 0.000711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2515 2516 0.976525 0.000917 0.007179 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2516 2517 0.999981 -0.021517 -0.031589 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2517 2518 1.006320 0.013775 -0.006269 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2518 2519 1.004020 0.031642 -0.018711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2519 2520 -0.011945 -0.989462 -1.582180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2520 2521 0.955626 0.012950 0.008154 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2521 2522 0.978242 0.026872 0.006880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2522 2523 1.020750 -0.002714 0.005289 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2523 2524 0.040196 -1.041050 -1.557590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2524 2525 1.002630 0.024244 -0.028573 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2525 2526 1.007040 0.034427 -0.019841 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2526 2527 1.025940 0.034152 -0.001530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2527 2528 -0.030556 1.040350 1.571330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2528 2529 1.016070 -0.015830 -0.008742 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2529 2530 1.006910 -0.003724 -0.023501 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2530 2531 0.952368 -0.023046 -0.004493 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2531 2532 -1.031230 -0.035047 3.131160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2532 2533 1.013620 -0.019766 -0.002027 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2533 2534 0.996564 -0.006384 -0.007300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2534 2535 0.961255 -0.019420 0.000497 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2535 2536 0.034682 1.008480 1.579875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2536 2537 1.010280 -0.008966 0.000576 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2537 2538 1.004140 0.010468 0.011983 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2538 2539 1.007280 -0.014359 0.009200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2539 2540 0.029741 -0.964773 -1.557985 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2540 2541 1.010850 -0.004408 0.019785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2541 2542 0.993392 -0.001499 0.050997 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2542 2543 1.003120 0.023077 0.031096 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2543 2544 -0.033161 -1.015750 -1.534690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2544 2545 1.012330 -0.010048 0.019830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2545 2546 1.005530 0.036239 0.000528 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2546 2547 1.004700 -0.064724 -0.024121 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2547 2548 -0.027022 1.013050 1.585690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2548 2549 0.983559 0.026136 -0.062073 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2549 2550 0.987719 -0.024198 -0.026476 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2550 2551 0.949905 -0.015036 -0.012079 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2551 2552 0.005566 0.996513 1.534385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2552 2553 1.026370 -0.056116 0.005599 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2553 2554 1.034580 -0.000948 -0.047032 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2554 2555 0.993381 -0.000922 -0.011640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2555 2556 0.001726 0.998735 1.590370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2556 2557 1.000040 -0.021764 -0.028047 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2557 2558 0.977222 0.007958 0.042403 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2558 2559 1.002540 0.000133 0.004763 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2559 2560 0.007190 -1.009730 -1.562290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2560 2561 1.059860 0.030545 -0.039105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2561 2562 0.996955 0.022855 -0.009136 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2562 2563 0.984247 -0.015238 0.039780 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2563 2564 -0.001139 -1.007550 -1.544995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2564 2565 1.006370 0.004958 -0.035585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2565 2566 0.983329 0.009109 0.009963 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2566 2567 1.009350 0.015927 -0.016303 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2567 2568 1.013130 -0.014550 -0.021094 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2568 2569 1.001080 0.017426 -0.028767 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2569 2570 1.044920 -0.037594 0.038587 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2570 2571 0.947230 -0.006970 0.044905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2571 2572 -0.003718 -1.010410 -1.600570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2572 2573 0.976291 -0.037995 -0.000237 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2573 2574 1.010940 0.007439 0.023716 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2574 2575 1.005770 -0.002686 -0.010547 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2575 2576 -0.002166 1.029400 1.560630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2576 2577 0.969704 0.006178 0.011721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2577 2578 1.020980 -0.013177 -0.010177 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2578 2579 1.000200 0.021216 0.002887 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2579 2580 0.031278 0.999896 1.591745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2580 2581 0.976488 -0.005630 0.038378 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2581 2582 1.020950 0.046721 -0.066756 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2582 2583 0.973970 -0.019040 -0.011576 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2583 2584 -1.034930 0.026163 3.120380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2584 2585 1.023780 0.054077 -0.025966 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2585 2586 0.992401 -0.024982 0.007958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2586 2587 0.978174 0.028697 -0.019138 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2587 2588 -0.991739 0.014043 3.135835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2588 2589 0.983124 -0.009585 0.019409 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2589 2590 0.988444 -0.065570 0.005201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2590 2591 0.988775 0.036641 0.036638 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2591 2592 -1.034040 0.027666 -3.114185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2592 2593 0.996344 -0.007121 0.002953 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2593 2594 0.980607 0.035752 -0.011081 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2594 2595 1.011270 0.008212 0.011048 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2595 2596 0.005671 1.014980 1.567240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2596 2597 1.008770 0.031534 -0.007253 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2597 2598 1.029190 0.020126 0.039362 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2598 2599 0.987402 -0.014522 0.004418 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2599 2600 0.024789 1.001140 1.580945 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2600 2601 1.012480 -0.017861 0.015530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2601 2602 1.004980 -0.015154 -0.019854 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2602 2603 1.000260 -0.008299 0.004817 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2603 2604 -1.007440 0.023920 3.139870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2604 2605 1.014910 -0.023570 -0.017505 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2605 2606 1.021180 -0.023134 -0.018415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2606 2607 1.033080 -0.003327 0.013399 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2607 2608 0.005722 0.991335 1.592690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2608 2609 0.999341 -0.032959 -0.053885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2609 2610 0.967245 -0.034448 0.013383 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2610 2611 0.966967 0.003459 -0.011045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2611 2612 0.031466 -0.965304 -1.570230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2612 2613 0.989573 -0.012328 -0.005934 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2613 2614 0.979051 -0.018950 0.041517 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2614 2615 0.996498 -0.020305 0.005483 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2615 2616 0.001744 0.984127 1.565990 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2616 2617 1.017330 -0.015515 0.017563 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2617 2618 0.978097 -0.035117 0.002221 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2618 2619 1.004590 -0.000950 -0.038989 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2619 2620 0.007133 0.989692 1.594875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2620 2621 0.979856 0.002194 0.035274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2621 2622 0.961244 0.026991 -0.034547 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2622 2623 0.944850 0.011921 0.009610 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2623 2624 0.027901 -1.006550 -1.543855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2624 2625 0.985052 -0.012908 0.005113 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2625 2626 1.002960 -0.008341 -0.013257 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2626 2627 1.029470 -0.004407 0.012383 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2627 2628 -0.015342 1.008470 1.585535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2628 2629 1.030810 0.008563 0.020588 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2629 2630 0.988316 -0.015516 0.018086 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2630 2631 0.987842 -0.043459 -0.009612 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2631 2632 0.007913 0.977768 1.577200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2632 2633 0.978632 -0.014704 -0.009594 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2633 2634 0.995650 -0.024250 0.018591 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2634 2635 1.018810 -0.019919 -0.012877 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2635 2636 1.011840 0.023149 0.024625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2636 2637 0.993604 -0.015338 0.029937 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2637 2638 1.005250 0.052719 -0.046081 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2638 2639 0.981526 0.022333 -0.005391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2639 2640 -0.006802 -1.008270 -1.573190 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2640 2641 0.990960 0.008862 0.003062 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2641 2642 1.004730 -0.002479 -0.012191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2642 2643 0.984184 0.046791 0.041509 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2643 2644 -1.003540 0.005754 3.139830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2644 2645 1.019790 -0.036897 -0.011365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2645 2646 1.020130 0.033542 0.019910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2646 2647 1.031890 0.018279 0.010080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2647 2648 -1.005700 0.003971 -3.132960 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2648 2649 1.010270 -0.014716 -0.027336 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2649 2650 1.001240 -0.003960 0.007393 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2650 2651 1.022820 -0.015281 0.027613 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2651 2652 0.030175 -0.995920 -1.560325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2652 2653 0.958399 0.012936 0.015682 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2653 2654 0.964300 -0.016478 -0.007502 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2654 2655 0.977275 -0.028211 0.002334 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2655 2656 -0.026504 0.941574 1.555855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2656 2657 1.022060 -0.018502 0.000432 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2657 2658 0.992838 -0.001822 0.023570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2658 2659 0.966286 0.006732 -0.014604 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2659 2660 -0.988917 -0.014257 3.105950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2660 2661 1.025310 -0.018150 -0.007142 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2661 2662 0.997025 -0.004987 0.016792 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2662 2663 0.979572 0.014225 0.020354 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2663 2664 0.036029 -0.997376 -1.577840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2664 2665 1.029200 -0.002306 -0.028280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2665 2666 1.012430 0.011073 -0.033181 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2666 2667 1.016230 0.011740 0.018467 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2667 2668 -0.054041 0.991373 1.565280 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2668 2669 0.973294 -0.001801 0.019485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2669 2670 1.000770 -0.008036 -0.022137 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2670 2671 0.990828 0.000318 0.025151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2671 2672 0.021806 -0.993917 -1.575450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2672 2673 0.999649 -0.000226 0.006075 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2673 2674 0.997989 -0.001386 -0.023141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2674 2675 0.984877 -0.007442 0.027059 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2675 2676 -0.980244 0.008222 -3.131625 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2676 2677 0.992981 0.006796 0.020719 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2677 2678 0.967876 0.059901 -0.000683 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2678 2679 1.054860 0.004162 0.036847 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2679 2680 0.014926 1.007980 1.571675 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2680 2681 1.016410 0.012327 0.026350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2681 2682 1.002490 0.023579 -0.063210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2682 2683 1.006920 -0.002750 0.008142 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2683 2684 0.044367 -1.013720 -1.577935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2684 2685 1.001620 0.000420 0.030050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2685 2686 1.025410 -0.005786 -0.002012 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2686 2687 1.010420 -0.018407 0.006984 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2687 2688 -1.005980 -0.021517 -3.110420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2688 2689 0.996324 0.001011 0.021771 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2689 2690 1.022460 0.018811 -0.006480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2690 2691 1.012040 -0.035256 -0.007479 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2691 2692 -0.971418 0.016225 -3.122285 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2692 2693 1.010460 -0.033049 -0.045335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2693 2694 0.983227 -0.019670 -0.033791 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2694 2695 1.018560 0.007524 0.012794 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2695 2696 -0.998356 0.004728 3.122075 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2696 2697 1.024270 0.014323 0.011166 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2697 2698 1.022690 -0.043679 0.001863 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2698 2699 0.963962 0.041828 -0.058570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2699 2700 -0.978435 -0.014490 3.127960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2700 2701 1.037480 0.030260 0.027065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2701 2702 1.043470 0.003407 -0.012266 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2702 2703 1.003060 -0.036924 0.021386 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2703 2704 0.001601 1.016020 1.538585 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2704 2705 0.967411 0.008063 0.003795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2705 2706 0.982967 0.014053 -0.033533 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2706 2707 0.995136 0.027239 0.019414 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2707 2708 0.025409 -0.994799 -1.565225 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2708 2709 1.016600 0.044091 0.001606 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2709 2710 1.002260 0.027744 -0.020415 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2710 2711 1.009940 0.000674 0.013382 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2711 2712 0.002035 -0.996933 -1.538820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2712 2713 1.021500 -0.024379 0.022519 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2713 2714 0.990908 -0.027228 -0.025676 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2714 2715 1.012780 0.016911 0.013203 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2715 2716 1.042150 0.024499 0.021559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2716 2717 0.997581 -0.009229 0.030976 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2717 2718 1.016870 -0.009794 -0.012968 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2718 2719 1.030480 -0.045470 -0.003344 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2719 2720 -1.015590 0.011203 -3.118740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2720 2721 0.988251 -0.017214 0.002838 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2721 2722 1.009910 0.022868 -0.022846 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2722 2723 1.036930 0.013254 -0.008551 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2723 2724 -0.992572 0.029954 -3.119395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2724 2725 0.990565 -0.029281 0.059070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2725 2726 1.021910 0.012625 -0.024848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2726 2727 0.971779 -0.034815 -0.001434 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2727 2728 -0.008257 -1.030740 -1.599520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2728 2729 0.993570 -0.012805 0.017762 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2729 2730 1.007430 0.039659 -0.004132 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2730 2731 1.042410 -0.010424 -0.016020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2731 2732 -1.011330 -0.003181 -3.136895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2732 2733 0.998816 0.000856 0.044878 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2733 2734 1.017510 0.031519 0.023774 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2734 2735 1.012890 -0.038101 0.004617 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2735 2736 -0.996330 -0.001944 -3.130540 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2736 2737 1.021830 0.002296 0.000769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2737 2738 1.010670 0.023052 0.027191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2738 2739 1.004500 -0.008408 -0.008467 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2739 2740 -0.967826 -0.037447 -3.101145 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2740 2741 1.005580 0.007925 0.030105 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2741 2742 1.026280 0.032292 -0.014371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2742 2743 0.995761 0.053594 -0.014257 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2743 2744 -1.003820 0.005106 3.136215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2744 2745 1.004250 -0.000317 0.008929 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2745 2746 0.957606 0.003090 -0.005132 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2746 2747 1.013090 -0.033207 0.017694 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2747 2748 0.030165 -0.962281 -1.574060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2748 2749 1.024940 -0.004027 -0.004170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2749 2750 0.998841 -0.003074 0.011394 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2750 2751 0.985981 0.010478 0.011414 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2751 2752 -1.011500 -0.024271 3.128470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2752 2753 1.005090 -0.023216 -0.003178 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2753 2754 1.015220 -0.014182 0.028613 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2754 2755 1.018290 -0.024871 -0.025220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2755 2756 -1.003430 -0.032490 -3.091170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2756 2757 0.987912 0.001077 -0.040001 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2757 2758 0.991127 0.014479 0.013727 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2758 2759 0.976544 -0.007568 0.001015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2759 2760 -0.977498 0.053981 -3.136745 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2760 2761 1.002700 -0.003736 -0.031711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2761 2762 0.997763 0.019986 -0.004118 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2762 2763 0.988149 -0.012439 -0.021309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2763 2764 -0.009858 -1.020110 -1.540260 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2764 2765 1.037190 -0.006954 0.011359 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2765 2766 1.006130 0.027376 0.026457 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2766 2767 1.020050 -0.026575 0.021683 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2767 2768 -1.012670 -0.024303 -3.118775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2768 2769 1.001200 -0.002950 0.006668 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2769 2770 0.993216 0.010407 0.032544 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2770 2771 1.018570 -0.014331 0.014711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2771 2772 -1.031550 -0.001962 -3.119760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2772 2773 1.013360 0.016951 -0.012332 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2773 2774 1.010190 -0.036899 0.023952 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2774 2775 0.991095 -0.002216 -0.031196 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2775 2776 -0.011470 -1.000670 -1.528940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2776 2777 0.976581 0.012713 0.037061 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2777 2778 0.997798 -0.019065 0.026440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2778 2779 0.957119 -0.009488 0.001212 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2779 2780 0.021778 -0.998726 -1.541675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2780 2781 1.017480 -0.026751 0.021024 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2781 2782 0.972341 -0.013938 0.002826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2782 2783 1.020970 -0.062003 -0.041947 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2783 2784 -0.017293 -0.978436 -1.556700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2784 2785 1.021560 -0.033653 0.008355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2785 2786 1.033670 -0.015221 0.004567 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2786 2787 1.037600 -0.013239 -0.004847 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2787 2788 -0.020474 -1.006960 -1.540390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2788 2789 1.047050 0.007804 0.045189 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2789 2790 1.019010 -0.022033 -0.002676 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2790 2791 1.031340 -0.020549 0.033136 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2791 2792 -0.977847 0.012812 -3.118705 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2792 2793 0.993443 0.014183 -0.008205 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2793 2794 0.988130 -0.002052 0.006414 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2794 2795 1.036340 0.015252 -0.002498 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2795 2796 0.010786 -0.991349 -1.577790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2796 2797 1.022840 -0.017920 -0.043101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2797 2798 1.005120 -0.008266 0.003406 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2798 2799 1.026410 -0.034886 0.038316 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2799 2800 -0.022505 -1.042210 -1.602790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2800 2801 1.007870 0.002592 -0.023723 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2801 2802 0.994095 -0.043818 -0.001576 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2802 2803 0.993646 0.008640 -0.036874 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2803 2804 -1.004350 -0.036364 3.123790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2804 2805 0.960908 0.018947 -0.027339 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2805 2806 0.982568 0.035860 -0.014321 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2806 2807 1.049850 -0.022659 0.011392 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2807 2808 -0.007134 1.031370 1.591745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2808 2809 1.002810 0.002313 0.003150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2809 2810 1.002990 0.003580 0.018626 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2810 2811 1.027240 0.019647 0.023887 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2811 2812 -0.015855 -0.990595 -1.572955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2812 2813 0.989364 0.024907 -0.000754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2813 2814 1.025990 -0.046769 -0.003461 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2814 2815 0.998673 0.043010 -0.005993 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2815 2816 0.011728 -1.032740 -1.542360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2816 2817 0.992600 -0.016130 0.012273 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2817 2818 0.969988 0.010409 0.002084 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2818 2819 0.991991 -0.026672 -0.021224 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2819 2820 0.018667 0.962607 1.541820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2820 2821 1.039520 0.048674 0.027016 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2821 2822 0.983641 -0.017363 -0.032602 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2822 2823 0.995486 -0.026001 0.026851 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2823 2824 0.021588 -1.013210 -1.531260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2824 2825 0.987154 -0.015331 0.000452 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2825 2826 1.020660 -0.008477 0.026782 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2826 2827 0.972462 -0.022776 0.014529 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2827 2828 0.001002 0.989616 1.563720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2828 2829 0.962607 -0.026840 -0.012943 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2829 2830 0.959035 -0.023510 0.003769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2830 2831 0.992401 0.047971 0.044332 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2831 2832 0.033301 0.998961 1.551395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2832 2833 0.995844 0.002860 -0.002008 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2833 2834 1.014730 0.031986 -0.017846 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2834 2835 1.025720 -0.023854 0.014140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2835 2836 0.011713 -0.995912 -1.563605 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2836 2837 1.017240 -0.027877 -0.018569 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2837 2838 0.987415 -0.008038 -0.003163 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2838 2839 1.018770 -0.013337 0.003896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2839 2840 -0.018985 0.979113 1.576775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2840 2841 1.040510 -0.004036 0.031537 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2841 2842 1.000060 0.011258 -0.027268 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2842 2843 0.978551 -0.014215 -0.023891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2843 2844 1.022220 0.015610 -0.034098 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2844 2845 1.012230 -0.021814 0.013102 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2845 2846 1.000540 -0.020415 0.015601 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2846 2847 1.000140 0.013666 0.040383 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2847 2848 0.006214 0.979603 1.572770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2848 2849 0.971837 0.011227 -0.005020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2849 2850 0.976713 0.008125 -0.030314 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2850 2851 1.019970 -0.000770 0.041358 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2851 2852 0.005544 1.013860 1.541300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2852 2853 1.019150 0.015311 -0.018391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2853 2854 1.013280 0.024962 -0.015790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2854 2855 0.958794 0.004062 -0.016543 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2855 2856 0.033886 -0.997440 -1.570280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2856 2857 0.992447 0.029367 -0.025419 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2857 2858 1.004650 -0.028164 0.008315 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2858 2859 1.021950 0.051418 -0.025410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2859 2860 -1.026920 0.013534 -3.138965 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2860 2861 0.996195 0.020259 -0.000942 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2861 2862 0.995985 0.004240 -0.032042 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2862 2863 1.032940 -0.022457 -0.016529 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2863 2864 -1.003990 0.018355 -3.128770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2864 2865 1.007260 -0.010953 0.018554 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2865 2866 0.994487 -0.015202 0.018815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2866 2867 0.999958 -0.022810 0.052579 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2867 2868 0.015650 -1.011780 -1.554640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2868 2869 1.015220 -0.010405 0.064086 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2869 2870 1.002550 -0.037283 -0.012580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2870 2871 0.993873 -0.001312 -0.026829 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2871 2872 -0.015496 -0.992639 -1.570955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2872 2873 0.976310 -0.020022 -0.000169 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2873 2874 1.012630 -0.040582 -0.019391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2874 2875 1.031060 0.007076 -0.012887 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2875 2876 -0.011463 1.003950 1.556835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2876 2877 0.961769 -0.009444 -0.022980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2877 2878 1.028950 -0.033197 0.028214 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2878 2879 0.978274 -0.024873 0.023622 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2879 2880 0.015975 -1.013850 -1.569155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2880 2881 1.000110 0.000539 0.022955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2881 2882 1.001900 0.036002 -0.001574 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2882 2883 1.009340 0.011900 -0.002420 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2883 2884 0.014164 1.008070 1.602025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2884 2885 1.028990 -0.026388 -0.014760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2885 2886 1.015090 0.013922 0.010741 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2886 2887 1.004450 -0.063117 0.001776 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2887 2888 0.001424 -1.027230 -1.540895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2888 2889 1.032820 0.014000 -0.013757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2889 2890 0.987343 -0.021351 0.016685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2890 2891 1.019140 0.018025 0.019889 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2891 2892 -0.008240 1.020320 1.585365 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2892 2893 1.001550 -0.022703 0.019240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2893 2894 1.004270 -0.001822 -0.004207 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2894 2895 1.031220 -0.024904 0.007401 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2895 2896 -0.039929 -1.027380 -1.582675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2896 2897 1.013130 0.017634 -0.016469 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2897 2898 0.999414 -0.017737 0.007214 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2898 2899 1.002400 0.035070 0.014154 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2899 2900 -0.999026 0.000149 -3.080690 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2900 2901 1.004260 0.003587 -0.029173 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2901 2902 1.010220 -0.003167 0.004046 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2902 2903 1.014940 -0.004698 -0.012489 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2903 2904 -0.995950 -0.007645 3.140100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2904 2905 1.030080 -0.019404 0.034870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2905 2906 1.048390 0.034364 0.032566 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2906 2907 1.011820 -0.023392 -0.015849 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2907 2908 -0.989741 0.007428 3.116725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2908 2909 1.016590 0.011892 -0.015966 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2909 2910 0.998109 -0.010367 0.010662 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2910 2911 1.011630 0.009822 -0.012851 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2911 2912 0.013964 1.011420 1.594870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2912 2913 1.023120 0.024857 0.026373 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2913 2914 1.024880 -0.018936 -0.042078 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2914 2915 0.995993 -0.070615 0.039822 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2915 2916 -0.993659 0.016830 3.104255 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2916 2917 1.004900 0.056664 -0.029210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2917 2918 1.028590 0.026529 -0.004719 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2918 2919 1.038980 0.006681 -0.027944 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2919 2920 0.004279 -0.983973 -1.586235 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2920 2921 1.011970 0.007374 0.001892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2921 2922 0.979387 0.009373 0.042565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2922 2923 0.971936 -0.006456 -0.018644 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2923 2924 0.012787 -1.014390 -1.562460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2924 2925 0.960955 -0.033283 0.039464 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2925 2926 0.987199 0.012755 0.006270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2926 2927 0.990042 0.009911 -0.029139 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2927 2928 -0.013347 -1.003670 -1.623690 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2928 2929 0.981579 -0.012719 0.005130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2929 2930 1.021570 0.023280 0.015905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2930 2931 0.994768 0.023812 -0.000047 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2931 2932 -0.982008 -0.005613 -3.105475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2932 2933 1.024340 0.058055 0.008570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2933 2934 0.965431 0.032266 -0.046417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2934 2935 1.017790 -0.016027 -0.002710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2935 2936 -1.020130 -0.008964 3.103885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2936 2937 1.001050 0.020630 0.000495 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2937 2938 0.970688 0.006325 -0.007679 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2938 2939 1.023280 0.038712 0.024162 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2939 2940 -1.015010 0.031593 3.137690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2940 2941 1.011010 -0.037083 -0.005703 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2941 2942 1.009430 0.004082 0.013467 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2942 2943 0.981258 -0.012120 -0.028934 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2943 2944 -0.003730 -1.010510 -1.579730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2944 2945 1.011480 0.018309 -0.038124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2945 2946 1.019600 0.008857 0.040480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2946 2947 0.969378 0.022525 0.027407 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2947 2948 -0.008019 0.987384 1.606320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2948 2949 0.965265 -0.030686 -0.040612 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2949 2950 0.995730 -0.007599 -0.008740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2950 2951 0.997706 0.005772 0.034602 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2951 2952 -0.032460 0.993589 1.594015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2952 2953 0.991453 0.016916 -0.007594 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2953 2954 1.016920 -0.047744 0.028476 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2954 2955 0.990303 0.019731 0.022732 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2955 2956 -0.986956 0.002509 3.121450 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2956 2957 0.985486 -0.001759 -0.032019 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2957 2958 1.023280 0.006678 -0.011626 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2958 2959 1.026570 0.007830 0.000471 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2959 2960 -0.983144 0.023060 3.116135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2960 2961 0.965787 -0.035311 -0.029334 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2961 2962 0.975433 -0.007328 0.015097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2962 2963 1.006510 0.015197 0.002646 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2963 2964 0.003901 -1.027740 -1.525575 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2964 2965 1.002810 -0.011664 0.021805 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2965 2966 0.979011 0.033504 -0.041891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2966 2967 1.006860 -0.014917 0.005523 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2967 2968 0.027754 -0.952560 -1.547450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2968 2969 1.019280 -0.037401 0.070000 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2969 2970 0.995999 0.035825 -0.017993 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2970 2971 1.012960 -0.008028 0.025545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2971 2972 -0.995114 -0.001823 -3.140580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2972 2973 1.004520 0.014816 0.009322 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2973 2974 1.022860 0.019968 -0.013827 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2974 2975 0.974703 -0.014532 0.037357 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2975 2976 -0.005036 -0.995235 -1.580005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2976 2977 0.967418 -0.018829 -0.011460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2977 2978 0.999220 0.016715 -0.041678 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2978 2979 1.010460 -0.000049 -0.004651 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2979 2980 -1.021920 -0.002723 3.101865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2980 2981 1.003910 -0.013932 -0.014459 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2981 2982 1.029770 -0.024625 0.039804 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2982 2983 0.987649 -0.025314 -0.016000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2983 2984 -0.982962 0.021382 -3.130765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2984 2985 0.977620 0.007767 -0.011283 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2985 2986 1.014750 -0.003285 0.023941 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2986 2987 1.049360 0.014825 0.015027 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2987 2988 0.019128 -1.017890 -1.561470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2988 2989 0.941729 0.001676 -0.003234 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2989 2990 0.967853 -0.014148 0.046526 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2990 2991 0.975238 0.003791 0.029318 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2991 2992 0.000965 0.987860 1.550450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2992 2993 1.025030 0.005818 -0.012346 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2993 2994 0.972741 -0.008795 0.007417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2994 2995 0.985798 0.032731 0.025652 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2995 2996 -0.015097 1.051280 1.578605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2996 2997 1.012890 -0.038109 -0.010520 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2997 2998 0.983235 0.033434 -0.007614 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2998 2999 1.010300 0.054464 -0.023640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2999 3000 0.011849 -1.040770 -1.547435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3000 3001 0.949358 -0.010485 -0.055718 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3001 3002 1.017270 -0.007142 -0.011066 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3002 3003 1.014050 0.011289 -0.003207 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3003 3004 0.046428 -1.026420 -1.600270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3004 3005 1.019560 -0.025181 0.005208 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3005 3006 0.979318 -0.010385 0.024771 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3006 3007 0.997052 0.000346 -0.018414 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3007 3008 -0.994087 0.012978 -3.110570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3008 3009 0.962758 0.025130 -0.005374 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3009 3010 1.036380 0.021381 0.001032 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3010 3011 1.012720 -0.043121 -0.021959 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3011 3012 -1.025960 0.010271 3.133220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3012 3013 1.014640 -0.045891 0.004739 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3013 3014 1.012950 -0.012644 -0.026051 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3014 3015 0.991530 0.035044 0.015581 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3015 3016 0.044520 -1.007300 -1.559690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3016 3017 0.968854 -0.005499 0.013291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3017 3018 0.979440 0.007479 0.014491 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3018 3019 0.992653 0.004788 -0.052935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3019 3020 -0.964126 0.009243 3.129930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3020 3021 1.031100 -0.030236 -0.011338 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3021 3022 0.986029 0.012136 0.005728 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3022 3023 0.975331 -0.006301 -0.020147 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3023 3024 -0.009209 -0.958217 -1.568020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3024 3025 0.980007 0.023489 0.001994 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3025 3026 0.985674 0.010867 0.001853 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3026 3027 0.993694 0.025695 0.050792 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3027 3028 -0.985504 -0.006204 3.127075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3028 3029 0.970024 0.015404 0.017437 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3029 3030 1.005110 0.056684 0.004383 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3030 3031 0.975950 0.002719 -0.009759 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3031 3032 -0.999902 -0.017723 -3.131615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3032 3033 0.997774 -0.007012 -0.018885 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3033 3034 1.036450 0.044137 -0.015184 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3034 3035 1.008390 0.001449 -0.004229 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3035 3036 -0.003115 0.970590 1.614130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3036 3037 0.972989 0.003238 -0.023592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3037 3038 1.021430 -0.028384 -0.042218 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3038 3039 0.988378 0.021600 -0.015709 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3039 3040 -0.001502 -0.964919 -1.599850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3040 3041 1.007730 -0.011859 0.005283 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3041 3042 1.004550 0.012551 0.016890 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3042 3043 0.994287 0.061417 0.023001 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3043 3044 -0.981177 0.001469 -3.114580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3044 3045 0.995829 0.005394 -0.009163 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3045 3046 0.997640 -0.052449 -0.015499 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3046 3047 1.006330 0.019041 -0.027666 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3047 3048 0.011811 1.018760 1.558930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3048 3049 0.989573 0.021750 0.024446 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3049 3050 0.970189 0.033208 0.001848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3050 3051 0.986668 -0.007082 0.014097 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3051 3052 0.998260 -0.010288 0.009709 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3052 3053 1.000550 0.001628 -0.042894 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3053 3054 0.970424 0.035196 0.003228 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3054 3055 0.986476 -0.002696 0.011254 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3055 3056 -0.010733 -0.991533 -1.589520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3056 3057 0.992650 0.003868 -0.029996 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3057 3058 0.993704 -0.023899 0.033262 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3058 3059 0.994726 0.021959 0.008969 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3059 3060 0.021336 -1.041730 -1.563435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3060 3061 1.000840 0.019049 -0.009598 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3061 3062 1.009340 -0.000537 0.020146 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3062 3063 1.019300 0.017017 0.022076 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3063 3064 -0.020555 0.964837 1.588865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3064 3065 1.047360 0.043389 0.016025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3065 3066 1.005810 -0.021976 -0.013852 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3066 3067 0.986095 -0.026854 0.047895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3067 3068 -0.007238 -0.982568 -1.564335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3068 3069 1.016010 -0.021676 -0.040092 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3069 3070 0.983223 -0.006413 -0.005669 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3070 3071 0.989032 -0.030844 -0.020644 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3071 3072 -0.043996 0.976317 1.590545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3072 3073 0.979204 0.001265 0.005067 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3073 3074 1.015500 -0.020200 -0.015325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3074 3075 0.952273 0.016423 -0.002412 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3075 3076 0.025820 1.037310 1.635950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3076 3077 0.988828 -0.000432 0.011981 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3077 3078 1.017420 -0.013459 0.009159 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3078 3079 1.011370 0.005204 -0.018371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3079 3080 0.009498 0.999466 1.617350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3080 3081 0.977010 0.004558 -0.037296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3081 3082 1.019940 0.035683 0.004165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3082 3083 0.989132 0.008040 0.019208 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3083 3084 -0.017071 1.001760 1.560160 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3084 3085 0.979637 0.004384 0.021874 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3085 3086 0.996995 -0.060487 0.002529 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3086 3087 1.002230 -0.003233 0.029342 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3087 3088 0.023995 -1.003350 -1.541510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3088 3089 0.940594 -0.009397 -0.026896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3089 3090 0.974666 -0.016348 -0.042144 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3090 3091 1.003470 -0.035096 0.013264 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3091 3092 -0.005868 -0.982225 -1.566250 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3092 3093 1.002190 -0.012114 0.012652 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3093 3094 1.018750 -0.019448 -0.004164 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3094 3095 0.961561 -0.009705 -0.011382 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3095 3096 -0.993661 -0.007216 -3.137155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3096 3097 1.024260 -0.023602 0.004550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3097 3098 1.016880 -0.021928 0.011957 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3098 3099 1.030110 0.005020 0.015941 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3099 3100 0.006887 -0.968244 -1.591170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3100 3101 0.997617 0.027980 0.007194 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3101 3102 1.009040 0.033521 0.020326 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3102 3103 0.996551 -0.024225 0.005769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3103 3104 -0.974752 -0.017535 3.133375 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3104 3105 0.986964 -0.028888 0.017493 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3105 3106 0.995174 -0.022733 0.017789 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3106 3107 0.982591 -0.030628 -0.008239 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3107 3108 -1.026500 0.002373 3.135610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3108 3109 1.002680 0.017837 0.007957 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3109 3110 1.016400 0.007271 0.021670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3110 3111 0.993447 0.001830 -0.018438 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3111 3112 1.002120 -0.015360 0.001444 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3112 3113 1.012870 0.057076 -0.008499 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3113 3114 0.957435 0.003161 0.038060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3114 3115 0.980179 0.017681 -0.008806 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3115 3116 -0.017812 -0.988353 -1.541850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3116 3117 1.023200 0.003165 -0.033199 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3117 3118 0.997735 -0.043241 -0.042918 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3118 3119 1.037020 -0.010359 0.045504 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3119 3120 0.042475 1.030040 1.567820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3120 3121 0.973994 -0.012334 -0.002721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3121 3122 1.034400 0.017841 0.013789 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3122 3123 0.972621 0.011912 -0.024788 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3123 3124 -0.038270 -1.019300 -1.588510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3124 3125 1.015080 0.015497 -0.029148 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3125 3126 0.990254 0.004846 -0.023872 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3126 3127 0.981534 0.013225 -0.005629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3127 3128 0.970137 -0.001881 -0.018629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3128 3129 1.019730 -0.010017 -0.025745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3129 3130 0.941815 0.012729 -0.031649 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3130 3131 1.000640 -0.034665 0.003879 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3131 3132 0.034001 -1.009330 -1.555470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3132 3133 1.016670 -0.001609 -0.002730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3133 3134 1.028470 -0.036706 -0.012960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3134 3135 1.034290 0.027922 -0.019636 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3135 3136 -0.016567 -1.041300 -1.586895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3136 3137 1.007340 0.013588 -0.039274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3137 3138 1.010140 0.004208 0.001581 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3138 3139 0.991597 -0.006025 -0.023172 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3139 3140 -0.028050 -1.003610 -1.600940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3140 3141 1.050590 0.003219 -0.003656 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3141 3142 0.991284 0.024321 -0.003533 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3142 3143 0.981163 -0.044330 -0.009230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3143 3144 -0.981978 -0.013366 -3.137690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3144 3145 1.002050 -0.013540 0.005833 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3145 3146 1.028420 -0.025293 0.014064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3146 3147 0.995370 0.008368 -0.019039 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3147 3148 0.995589 -0.017235 0.011284 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3148 3149 1.055110 0.013693 0.016356 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3149 3150 1.023200 0.050185 -0.016047 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3150 3151 0.994718 0.009692 0.019269 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3151 3152 -0.003944 -0.992141 -1.551905 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3152 3153 0.979559 -0.007663 -0.015114 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3153 3154 1.001660 0.008204 0.005533 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3154 3155 1.027980 -0.004486 -0.010784 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3155 3156 -0.018447 -1.019740 -1.554190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3156 3157 1.020680 0.031927 -0.015066 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3157 3158 1.002990 -0.005137 -0.010779 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3158 3159 0.985680 0.032260 0.024298 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3159 3160 -0.035610 1.022710 1.551670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3160 3161 1.033370 -0.009778 0.019052 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3161 3162 1.021200 -0.003259 0.035468 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3162 3163 1.001500 -0.007462 -0.027754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3163 3164 0.030797 0.980349 1.535695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3164 3165 1.004780 -0.004670 -0.015989 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3165 3166 0.960869 0.033826 -0.013817 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3166 3167 1.022110 -0.052553 0.006934 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3167 3168 0.031783 0.972155 1.588810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3168 3169 0.976831 0.020663 0.004533 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3169 3170 1.008120 -0.011115 0.015607 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3170 3171 1.000490 0.014178 0.028764 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3171 3172 -1.008730 0.033128 -3.123165 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3172 3173 0.998576 -0.015849 0.014313 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3173 3174 1.011310 0.015076 -0.002227 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3174 3175 1.040810 -0.024728 -0.016309 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3175 3176 -1.018250 -0.016349 3.105315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3176 3177 1.024810 -0.001298 -0.027570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3177 3178 1.011150 -0.026270 -0.013087 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3178 3179 1.006910 0.013363 -0.001559 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3179 3180 -0.994480 -0.050674 3.105890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3180 3181 0.969415 -0.058401 -0.023989 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3181 3182 0.997888 0.016144 -0.019391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3182 3183 0.999458 -0.012818 -0.060827 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3183 3184 -1.058080 0.019248 -3.100690 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3184 3185 1.013730 0.008796 -0.012528 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3185 3186 1.013490 0.014673 -0.010603 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3186 3187 1.021390 0.007879 -0.004339 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3187 3188 0.020804 -1.005400 -1.576720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3188 3189 0.988311 -0.020583 0.000070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3189 3190 1.011590 -0.038495 -0.020572 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3190 3191 0.970249 0.015649 -0.009291 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3191 3192 0.003827 -0.986228 -1.550595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3192 3193 0.994494 -0.017611 -0.015204 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3193 3194 0.966012 -0.001789 0.006856 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3194 3195 1.038210 0.010016 0.000571 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3195 3196 -0.015025 -0.998713 -1.587010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3196 3197 0.989508 0.013562 -0.002539 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3197 3198 1.004170 0.027873 -0.012518 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3198 3199 1.031390 -0.000549 0.034082 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3199 3200 -0.991136 0.026371 -3.120320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3200 3201 1.002790 -0.006385 0.006376 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3201 3202 1.022980 0.005412 -0.019201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3202 3203 0.979212 0.002242 0.022719 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3203 3204 0.020852 1.011780 1.594680 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3204 3205 0.978291 0.003959 0.013629 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3205 3206 1.004260 -0.012109 -0.011927 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3206 3207 1.012720 -0.019548 0.001462 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3207 3208 -0.007101 0.995182 1.549010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3208 3209 0.997039 -0.022550 0.003123 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3209 3210 1.005140 -0.003952 0.006149 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3210 3211 1.010480 -0.005612 0.023993 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3211 3212 0.026720 -0.993725 -1.578330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3212 3213 0.986010 0.047137 -0.041188 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3213 3214 1.036350 -0.023911 0.027648 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3214 3215 0.982395 0.008032 0.034460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3215 3216 -0.051563 1.042360 1.592880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3216 3217 0.981199 0.015844 0.015653 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3217 3218 0.995275 -0.017249 -0.031360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3218 3219 0.986383 -0.004405 -0.024771 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3219 3220 0.005746 -0.969143 -1.586610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3220 3221 0.996395 -0.012152 -0.003680 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3221 3222 0.981031 0.008997 -0.029051 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3222 3223 1.018790 0.015672 0.017211 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3223 3224 -1.019030 0.024485 3.134770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3224 3225 1.022830 -0.005479 -0.008353 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3225 3226 0.989587 -0.020687 -0.004629 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3226 3227 0.981982 0.007701 -0.025761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3227 3228 0.010294 1.049480 1.554695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3228 3229 1.003250 -0.009607 -0.004081 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3229 3230 1.009520 -0.009812 -0.012004 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3230 3231 0.998004 -0.008317 -0.000379 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3231 3232 -0.001194 -0.949646 -1.571535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3232 3233 1.007160 0.015357 0.046277 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3233 3234 0.999688 -0.025097 0.013792 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3234 3235 1.028760 0.003181 0.018568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3235 3236 0.009509 1.003530 1.575905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3236 3237 0.994913 -0.018592 0.017589 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3237 3238 0.970273 0.008640 0.035671 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3238 3239 1.014730 -0.008631 0.045111 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3239 3240 0.021401 1.000930 1.549060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3240 3241 0.994319 0.005962 0.011432 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3241 3242 1.020890 -0.004046 -0.056042 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3242 3243 1.011220 0.008063 0.014129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3243 3244 -0.028569 -0.975524 -1.549910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3244 3245 1.026990 0.003618 -0.000413 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3245 3246 0.985678 -0.019764 -0.011282 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3246 3247 1.002410 -0.051475 -0.001478 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3247 3248 -0.013734 -0.994023 -1.605235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3248 3249 0.992300 -0.025487 -0.032178 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3249 3250 1.006060 -0.022211 -0.010421 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3250 3251 1.023410 -0.007577 0.020018 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3251 3252 0.027151 1.038630 1.570945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3252 3253 0.984537 0.048160 0.002152 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3253 3254 1.029420 0.046449 0.007892 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3254 3255 1.063040 0.035190 -0.033454 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3255 3256 -0.003733 1.005170 1.539550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3256 3257 0.994021 0.018864 0.018979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3257 3258 0.968680 0.030430 0.035861 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3258 3259 1.001920 -0.006390 -0.011758 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3259 3260 0.005830 1.000990 1.592190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3260 3261 0.970383 0.012995 0.035362 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3261 3262 1.038540 -0.029174 0.005753 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3262 3263 0.963657 -0.033835 0.009946 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3263 3264 -1.002580 0.016192 3.101495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3264 3265 0.986377 -0.019337 0.024017 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3265 3266 1.008190 0.004562 0.020913 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3266 3267 1.012250 -0.008190 -0.029956 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3267 3268 0.047126 0.990677 1.570160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3268 3269 0.999563 -0.004261 -0.031949 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3269 3270 0.986505 0.009717 -0.011158 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3270 3271 0.994982 -0.004465 0.033282 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3271 3272 -0.001707 0.966667 1.572460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3272 3273 0.995110 -0.017087 0.019641 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3273 3274 0.989202 0.029826 -0.017958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3274 3275 1.004410 0.005848 -0.025087 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3275 3276 0.974643 0.008885 -0.047140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3276 3277 0.996159 0.006740 -0.010240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3277 3278 1.003740 -0.023628 0.045714 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3278 3279 1.046830 0.041642 -0.016180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3279 3280 -0.968141 0.011181 3.131685 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3280 3281 0.984484 -0.013169 0.006375 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3281 3282 1.033630 -0.003531 -0.001588 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3282 3283 1.002540 -0.003289 -0.030603 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3283 3284 0.021268 -0.995361 -1.585175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3284 3285 1.003310 -0.008733 0.036330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3285 3286 1.004240 -0.056349 -0.010371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3286 3287 1.009710 0.030077 -0.003553 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3287 3288 1.033450 -0.053486 -0.015676 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3288 3289 0.999968 -0.006819 0.022371 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3289 3290 1.008640 -0.001390 -0.041246 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3290 3291 1.013380 0.051969 0.048748 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3291 3292 -0.022554 -0.989052 -1.555150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3292 3293 1.010690 0.000425 -0.019124 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3293 3294 0.998470 -0.008427 0.021939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3294 3295 0.991732 0.018742 0.026621 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3295 3296 0.003514 0.999713 1.562760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3296 3297 1.004030 -0.021252 0.006814 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3297 3298 1.038520 -0.002479 -0.014731 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3298 3299 0.972708 -0.037792 0.005689 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3299 3300 -0.994057 0.012695 3.132305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3300 3301 0.982993 0.007534 -0.019544 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3301 3302 0.998298 -0.049185 0.028592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3302 3303 1.014460 0.025328 0.029283 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3303 3304 -0.020164 -1.004130 -1.587830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3304 3305 0.946001 -0.020358 -0.029386 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3305 3306 1.018220 -0.015113 -0.011063 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3306 3307 1.006600 0.020458 0.005237 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3307 3308 -0.024853 -0.994147 -1.580315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3308 3309 0.999317 -0.000938 -0.001445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3309 3310 1.004270 0.043327 -0.009342 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3310 3311 1.013180 -0.013152 0.017069 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3311 3312 -0.003540 0.997655 1.582365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3312 3313 1.007100 -0.016869 0.025065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3313 3314 1.013660 0.037597 -0.036825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3314 3315 0.957995 -0.019456 0.022756 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3315 3316 -1.003190 -0.019956 -3.138055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3316 3317 0.991117 -0.022885 -0.009468 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3317 3318 0.983881 -0.019107 -0.006666 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3318 3319 0.978531 0.013999 0.019585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3319 3320 -0.964764 -0.012120 3.132075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3320 3321 1.009660 -0.031282 -0.015696 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3321 3322 1.006300 -0.013102 0.022638 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3322 3323 1.005050 0.022625 -0.004783 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3323 3324 0.974548 0.013733 0.002643 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3324 3325 0.998534 -0.021741 0.022703 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3325 3326 1.011550 -0.026498 -0.021933 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3326 3327 0.978220 0.042031 0.025897 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3327 3328 -1.001210 0.012815 3.115090 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3328 3329 0.983243 0.006756 -0.022207 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3329 3330 1.035860 0.040321 0.000079 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3330 3331 0.989548 0.031210 -0.015153 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3331 3332 -0.990839 0.000080 -3.140470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3332 3333 0.978668 0.020714 -0.041135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3333 3334 1.030010 0.016320 0.043412 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3334 3335 0.987151 -0.005037 -0.001844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3335 3336 -0.026502 1.016620 1.566460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3336 3337 0.971185 0.000007 -0.028191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3337 3338 1.027990 -0.031862 -0.007255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3338 3339 1.035150 -0.013152 -0.007821 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3339 3340 0.987255 -0.046908 0.005789 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3340 3341 0.987192 -0.007479 0.013121 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3341 3342 0.968604 -0.036349 0.016676 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3342 3343 0.993689 0.014978 -0.009184 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3343 3344 -0.027298 -0.986601 -1.570760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3344 3345 1.017720 -0.001902 0.025172 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3345 3346 1.002580 0.007977 -0.005545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3346 3347 0.992045 -0.002418 0.004087 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3347 3348 -0.004922 0.993692 1.581410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3348 3349 0.988995 -0.045466 -0.017125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3349 3350 0.972563 0.066375 -0.020179 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3350 3351 0.975218 0.050133 0.021366 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3351 3352 0.007082 0.979028 1.560570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3352 3353 0.972766 0.026418 -0.020797 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3353 3354 1.008460 -0.006790 -0.009639 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3354 3355 0.982965 -0.019914 -0.047351 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3355 3356 -0.004909 -0.988526 -1.588320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3356 3357 1.015810 -0.010074 0.018889 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3357 3358 1.016810 0.061353 -0.012758 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3358 3359 1.009930 -0.007788 0.000875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3359 3360 -0.005262 -1.006070 -1.602710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3360 3361 1.009710 0.013225 -0.028916 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3361 3362 0.973774 0.005458 0.023706 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3362 3363 0.971329 -0.016467 -0.025716 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3363 3364 -0.002464 -1.028500 -1.579785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3364 3365 1.009260 -0.007530 0.037649 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3365 3366 1.002070 -0.027895 -0.007071 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3366 3367 1.007310 -0.019784 -0.002932 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3367 3368 -0.022902 0.992987 1.531495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3368 3369 1.010080 -0.010873 0.032327 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3369 3370 0.998794 -0.004979 0.031951 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3370 3371 1.014560 0.015757 -0.002000 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3371 3372 -0.995620 0.014788 3.099660 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3372 3373 0.997254 0.006841 -0.008868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3373 3374 0.993158 -0.002875 0.021010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3374 3375 0.995964 -0.020818 0.033474 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3375 3376 -0.017825 1.029740 1.582600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3376 3377 1.002470 0.020044 0.025792 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3377 3378 0.991185 0.012959 0.017153 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3378 3379 1.013930 0.006322 -0.035347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3379 3380 0.002187 1.000940 1.559045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3380 3381 0.990160 -0.021642 0.026874 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3381 3382 0.988236 -0.009134 0.028842 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3382 3383 1.027550 0.038226 -0.000143 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3383 3384 -0.013870 -0.956363 -1.569035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3384 3385 0.976551 0.012302 -0.018141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3385 3386 0.966227 -0.006554 -0.020180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3386 3387 1.020040 -0.017772 0.005620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3387 3388 0.006898 0.988254 1.571445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3388 3389 1.031480 0.015841 -0.010743 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3389 3390 0.972092 0.005104 -0.014101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3390 3391 0.995755 -0.004485 0.010979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3391 3392 -0.032529 0.984761 1.544280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3392 3393 0.958792 -0.025786 0.003015 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3393 3394 0.980095 0.010297 -0.035127 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3394 3395 0.980601 -0.009935 -0.009737 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3395 3396 -1.012890 0.003801 -3.129215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3396 3397 1.021020 0.047047 0.013570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3397 3398 0.994935 0.005898 -0.031826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3398 3399 0.985878 0.003018 -0.042914 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3399 3400 -0.023994 1.030890 1.573885 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3400 3401 0.979475 -0.030651 -0.035336 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3401 3402 1.019020 -0.007660 -0.010485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3402 3403 1.024270 -0.031548 -0.036707 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3403 3404 0.026544 0.965432 1.578560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3404 3405 1.021120 0.019263 -0.006886 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3405 3406 0.967448 0.006502 -0.003555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3406 3407 0.996180 0.004856 0.003670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3407 3408 -0.007997 -0.970019 -1.553350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3408 3409 0.984247 -0.021405 0.006653 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3409 3410 1.037620 0.019758 0.036146 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3410 3411 0.993571 0.000352 0.010621 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3411 3412 0.009931 1.015140 1.568940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3412 3413 0.988289 0.015752 0.066781 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3413 3414 1.015980 0.036492 0.024082 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3414 3415 0.979782 -0.009294 -0.012922 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3415 3416 0.012431 -0.979725 -1.592010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3416 3417 0.992631 0.028246 -0.012281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3417 3418 1.037560 0.049775 -0.018869 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3418 3419 0.990104 0.009483 0.009932 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3419 3420 -0.989299 -0.016609 -3.117245 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3420 3421 1.011220 -0.004058 0.025844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3421 3422 0.998743 -0.016821 -0.017242 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3422 3423 1.014890 0.006925 -0.003216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3423 3424 -0.026352 -0.984030 -1.603160 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3424 3425 1.009070 0.014879 -0.012290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3425 3426 1.019190 -0.035818 0.022013 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3426 3427 1.001610 -0.040134 -0.017427 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3427 3428 -0.983389 -0.030993 3.128890 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3428 3429 1.001200 0.006919 0.015115 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3429 3430 0.992492 -0.026385 -0.013170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3430 3431 0.999548 -0.025304 0.009985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3431 3432 0.000700 0.986876 1.575655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3432 3433 0.975706 -0.009326 0.017767 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3433 3434 0.987059 -0.011086 0.005335 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3434 3435 1.021300 0.023348 -0.013922 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3435 3436 -1.011110 -0.025837 3.141530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3436 3437 1.028840 0.003365 -0.024391 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3437 3438 0.993046 0.033949 -0.009721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3438 3439 0.988596 0.000471 -0.029776 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3439 3440 -0.024381 -0.997496 -1.570420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3440 3441 0.984994 -0.010701 -0.050178 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3441 3442 1.039270 0.018315 -0.006031 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3442 3443 0.994462 -0.019647 -0.026263 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3443 3444 -1.020820 -0.009946 -3.136575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3444 3445 0.997848 0.015083 -0.000618 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3445 3446 0.968514 0.004938 -0.039928 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3446 3447 1.012000 0.012928 -0.020559 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3447 3448 0.006940 -0.995464 -1.550270 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3448 3449 1.012430 0.017194 -0.014776 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3449 3450 1.012860 -0.008696 0.011483 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3450 3451 0.989045 -0.015434 -0.033236 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3451 3452 -0.966712 -0.016869 -3.137100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3452 3453 1.019170 0.033303 -0.024889 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3453 3454 0.988966 0.045130 -0.012500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3454 3455 1.005030 0.034708 0.003753 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3455 3456 -0.967105 0.022517 3.129360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3456 3457 0.975519 0.050836 0.001655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3457 3458 0.958945 -0.015681 0.026202 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3458 3459 1.021510 0.034336 -0.005266 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3459 3460 -0.010583 -1.032180 -1.568010 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3460 3461 1.015290 -0.015414 0.026738 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3461 3462 1.005570 -0.035481 -0.022295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3462 3463 0.999418 0.033903 0.016151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3463 3464 0.027271 -0.989602 -1.592530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3464 3465 0.966129 -0.026717 -0.009151 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3465 3466 0.984137 -0.030826 -0.019975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3466 3467 0.969697 0.003952 -0.013155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3467 3468 -1.025200 0.016253 -3.096445 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3468 3469 1.035110 0.001733 0.002697 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3469 3470 0.982730 -0.061135 0.013515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3470 3471 1.007350 0.005581 0.011867 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3471 3472 -1.014860 0.003771 3.140545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3472 3473 1.022080 0.024371 0.022842 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3473 3474 0.997731 -0.014095 0.031292 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3474 3475 1.006980 -0.000038 -0.021114 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3475 3476 -0.022124 -0.969834 -1.572095 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3476 3477 1.016190 0.012519 -0.047811 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3477 3478 1.010640 0.021958 -0.002557 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3478 3479 1.026950 -0.000437 0.021621 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3479 3480 -0.019308 1.011770 1.593585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3480 3481 1.019790 -0.009418 0.002508 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3481 3482 0.987497 0.038948 0.011711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3482 3483 1.012170 -0.020682 -0.018264 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3483 3484 -0.019261 -0.983232 -1.568625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3484 3485 1.021570 -0.022117 0.013223 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3485 3486 0.987755 0.013787 0.004222 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3486 3487 1.007470 -0.024479 0.021384 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3487 3488 0.004909 -0.990065 -1.574220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3488 3489 1.006360 -0.002062 0.025968 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3489 3490 0.996329 0.003036 0.010493 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3490 3491 1.028180 0.027322 0.048903 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3491 3492 0.002842 0.974513 1.602460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3492 3493 1.018600 0.014913 0.017451 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3493 3494 1.030430 -0.013492 -0.005179 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3494 3495 1.008730 -0.020997 -0.018531 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3495 3496 -0.003263 -1.000280 -1.565880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3496 3497 1.014890 0.002422 0.013907 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3497 3498 1.053930 -0.016927 -0.003412 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3498 3499 0.951435 0.043095 0.029398 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 5 9 0.033943 0.032439 -3.127400 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 10 0.044020 0.988477 -1.563530 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 8 14 0.015808 0.021059 3.128310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 7 15 -0.014728 -0.001595 -0.019579 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 21 26 -0.952140 -0.041846 3.134750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 19 27 -0.017616 -0.005218 1.567910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 40 51 2.977430 0.032654 3.121100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 7 55 -0.033505 -0.006809 -1.584070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 14 56 0.003854 0.000186 3.136015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 8 56 -0.019655 0.006738 0.012718 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 5 57 -0.048046 -0.007535 3.120335 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 47 64 -0.992098 -0.016459 3.122810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 43 68 0.993623 0.039194 -0.001061 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 45 69 -0.006758 -0.006796 -0.002136 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 83 101 -1.977040 -0.007033 3.116505 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 96 102 0.009822 -0.005774 -3.127340 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 79 103 -0.018687 -0.003386 1.557330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 79 105 -0.012583 -2.006310 -1.591245 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 108 113 1.003930 0.015909 -3.110170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 109 113 0.007893 0.022383 3.130288 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 107 115 -0.004603 0.010031 1.574593 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 107 116 -1.006620 0.031373 3.123185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 96 118 0.030695 0.001385 3.130305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 102 118 0.025841 -0.019824 0.019941 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 105 118 -0.978873 0.015246 -3.116610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 81 121 0.021299 0.020454 0.026723 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 82 122 0.015889 -0.005368 -0.026105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 105 122 1.027960 0.003379 -0.026745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 86 126 0.016650 0.001989 0.029570 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 130 138 1.056950 -0.992927 1.596510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 137 141 -0.015647 -0.033674 -3.138580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 136 144 0.005887 -0.029549 -0.014297 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 134 145 -1.018030 -0.005965 3.117790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 134 146 -1.991410 0.002261 3.123760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 139 147 -0.034861 -0.029734 0.011174 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 130 147 0.968708 0.048339 1.568600 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 131 147 -0.009658 -0.049102 1.512730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 150 159 1.007570 -0.027778 -1.566740 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 156 163 -1.024930 -0.001463 -3.119075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 154 164 -0.021340 -0.013376 -3.125920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 156 164 0.012303 -0.013795 -0.011030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 149 169 0.000313 -0.010342 3.130110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 133 171 -2.018960 -0.002866 -1.544005 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 92 172 -0.021347 -0.009751 0.033268 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 130 172 1.001470 1.016060 1.584110 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 94 174 0.009081 0.007000 -0.011171 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 120 174 -0.997476 1.018120 -1.611290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 78 175 0.995985 0.001641 -3.118425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 79 175 0.047171 -0.036224 3.118590 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 119 175 -0.011971 0.022700 1.596380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 94 176 -0.009378 -0.006867 3.109175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 93 177 0.029985 -0.030254 3.138285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 94 177 -0.992944 0.024181 3.126578 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 91 178 0.014004 1.027950 -1.565610 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 139 179 -0.009992 -0.001400 -3.130300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 92 179 -0.963062 -0.011130 3.073995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 130 179 1.018600 -0.003145 -1.583590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 145 180 1.019300 0.006052 -3.098830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 171 180 0.000054 1.026050 1.586015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 140 181 1.038800 0.019089 0.006004 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 133 181 -0.008724 -0.006345 0.008793 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 135 182 -1.050800 0.019972 0.024970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 134 182 -0.056552 0.047107 0.006526 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 136 182 0.011125 -0.015108 3.140875 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 128 189 -0.989149 -1.981080 1.557190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 127 191 -0.018618 0.033680 -3.133555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 203 211 0.012884 0.002148 -1.575530 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 202 212 -0.048296 -0.004273 -3.137170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 200 213 1.011940 0.041571 3.134295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 201 213 0.017884 0.000258 -3.140020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 199 215 0.014216 -0.005940 1.602290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 201 216 -1.975870 -0.981812 -1.535380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 196 220 -0.024594 -0.061977 0.047274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 197 221 0.001136 0.023364 0.047711 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 196 221 1.014520 -0.027180 -0.011414 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 199 222 -1.004040 0.039913 -0.005401 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 198 222 0.018732 0.024080 0.039628 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 200 223 -0.988228 0.007260 1.575675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 216 224 -0.011991 0.000445 -0.003093 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 219 226 -0.995612 -0.011419 0.028247 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 196 226 0.019514 0.031522 -3.095495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 195 227 -0.030778 0.000902 -1.585070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 193 228 0.996745 -0.026141 3.134685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 88 231 -1.001120 0.021493 0.004750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 190 232 0.019372 0.024358 -3.138620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 188 233 1.021870 -0.004737 -3.139330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 189 234 -0.990713 -0.015648 3.131995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 188 234 -0.004968 0.012445 -3.139420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 186 236 0.004458 0.021037 3.137025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 184 237 0.971251 -0.021497 -3.125840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 185 237 0.019916 -0.001845 3.126435 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 183 238 0.010910 -1.046940 1.525350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 184 238 0.033911 -0.006097 -3.120310 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 143 239 0.001108 -0.025039 1.565120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 135 239 0.026544 0.034611 1.572060 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 184 239 -0.981307 -0.018655 3.115705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 236 241 1.018000 -0.037901 3.114700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 237 242 -1.016310 -0.027431 3.121810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 235 243 -0.006977 -0.042663 -1.602185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 187 244 0.013253 0.976097 1.583208 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 252 258 0.016041 -0.029798 -3.127120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 250 259 1.022390 0.000242 0.028994 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 247 265 -0.002655 2.019930 1.589130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 279 286 0.032356 -0.967609 1.540430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 280 286 -0.016423 0.022912 3.128048 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 282 286 -1.970550 0.033416 3.139050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 279 288 -0.985267 0.000961 -3.126551 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 278 289 -1.012494 0.006856 3.129476 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 276 289 0.986065 -0.009846 3.113565 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 276 290 0.022782 -0.020032 -3.115300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 277 290 -0.972550 0.038508 -3.116130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 276 292 -0.984308 1.004310 1.591850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 274 293 -0.998769 0.007025 -3.127335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 272 294 -0.003504 -0.031233 -3.135695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 271 295 -0.006691 0.000162 -1.607125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 272 295 -1.018730 -0.021203 3.108140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 268 295 2.993540 -0.001041 -1.538720 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 270 295 0.995366 -0.001633 -1.557605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 271 296 0.982399 -0.013394 0.047216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 271 297 1.987350 0.006651 0.029979 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 324 328 1.979780 0.001746 -3.127450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 321 333 -0.043955 -0.046636 -3.134830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 317 337 0.023904 -0.001727 -3.137310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 314 338 0.988263 -0.976109 1.578510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 316 339 -1.015260 -0.017231 -3.141360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 314 339 0.972186 -0.019480 1.578410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 310 343 1.049060 -0.033210 -1.581450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 308 346 0.033858 0.002921 -3.102220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 262 349 -0.979658 0.044801 -0.052476 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 261 349 -0.028712 0.025899 0.017078 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 263 351 -0.007299 -0.006264 0.001009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 250 354 0.009201 -0.007471 -0.003875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 307 355 0.016016 -0.000361 -3.119010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 261 357 0.005463 0.022872 -0.006466 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 257 357 -0.007003 -0.012578 3.115570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 253 357 0.011823 0.014891 0.017195 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 264 358 -1.003200 -0.990045 1.543800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 257 358 -1.024290 0.014041 -3.120235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 249 359 -2.030730 -0.016039 -3.136325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 351 360 -0.985047 -0.017186 3.125815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 357 361 0.002213 0.007529 3.117775 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 357 362 -0.959250 -0.019954 3.118165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 307 363 0.035379 -0.014909 3.101965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 253 365 -0.040970 0.002650 -0.005650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 357 365 -0.016242 -0.031496 0.014277 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 353 365 -0.005924 -0.003726 -3.135135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 264 367 -1.010970 0.005725 1.552830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 264 368 -1.975460 -0.041576 3.128360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 360 368 -0.978143 -0.991113 -1.579015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 263 369 -0.025636 2.029780 1.592210 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 255 369 0.029259 2.000900 1.578770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 246 369 1.003270 -1.990310 -1.545795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 352 370 -1.005020 -3.007530 -1.516295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 370 374 0.985282 2.993520 1.599045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 343 376 -0.028924 0.984516 1.560110 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 323 379 0.011167 0.036256 1.614510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 333 380 -0.987006 -0.016189 -0.026352 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 322 380 -0.018954 0.013547 -3.108370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 333 381 -0.026370 0.047653 0.008255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 332 381 1.024040 0.017482 -0.013000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 318 383 0.993537 0.010490 1.581895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 334 383 0.983580 -0.013428 0.048271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 337 385 -0.025618 -0.006253 0.029142 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 316 386 -0.000379 0.009521 -3.133840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 343 390 -0.962859 -0.016296 -0.000633 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 312 391 -1.041640 -0.027316 -3.117335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 344 392 0.019701 -0.024825 -0.005928 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 308 393 0.958961 0.030394 -3.128220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 307 395 0.026539 -0.003537 -1.569130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 307 396 -0.975571 0.020043 -3.117470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 301 399 1.982140 0.024036 1.593465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 303 399 0.014051 -0.014608 1.562395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 300 399 3.016780 0.026357 1.551535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 303 400 1.026010 0.017202 -0.021088 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 339 403 -0.003385 -0.008583 -3.117650 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 340 404 -1.002570 -1.024710 -1.585800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 314 404 1.036810 0.988868 1.611500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 400 405 0.966934 0.025027 3.117555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 401 405 -0.002499 0.029736 -3.117160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 400 406 0.025658 0.027564 3.135835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 397 406 1.987610 -1.008710 1.538270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 399 407 -0.014670 -0.024863 1.516030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 302 408 1.010330 0.983108 1.570325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 303 409 -0.016580 1.966560 1.541865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 412 417 1.027580 -0.005463 3.131350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 413 417 0.006479 0.023387 3.137480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 412 418 0.025902 -0.023795 -3.129495 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 413 418 -1.003690 0.001786 3.138400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 411 420 1.000230 -0.022490 -0.026284 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 425 429 2.014390 2.017418 1.580811 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 426 430 1.005150 3.017500 1.552510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 440 446 -0.012974 -0.005554 -3.111665 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 440 448 -1.004610 1.018750 1.548080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 437 453 0.005577 0.050710 -0.003026 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 453 458 -1.005180 -0.011726 -3.128270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 453 461 0.002225 0.027011 0.009896 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 454 462 -0.000092 -0.012252 0.025286 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 438 462 -0.022174 -0.029616 0.039552 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 439 463 0.012663 -0.010816 -0.029155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 455 463 0.052926 0.013356 0.014485 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 446 464 0.009180 0.003776 3.137755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 469 473 -0.019209 -0.024285 3.131205 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 444 475 -1.001237 -0.009345 -1.570693 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 467 475 0.006740 -0.017902 1.571800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 443 475 -0.017355 -0.013213 1.584180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 472 478 -0.015134 0.000668 3.124930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 472 479 -0.991103 -0.020285 3.127400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 469 480 0.984987 0.040278 3.132835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 473 481 -0.001684 -0.010132 0.011227 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 447 486 -1.033630 0.006690 0.005394 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 455 486 0.003331 1.013440 -1.595985 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 446 486 0.012722 0.020413 0.061342 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 440 486 -0.016964 -0.031764 3.140730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 439 487 0.025696 -0.022539 -1.588530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 454 488 0.019571 0.013669 3.079845 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 448 488 0.009747 0.017729 0.018150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 453 489 -0.002706 -0.010749 3.116515 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 450 489 -1.005820 -0.010103 0.035925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 497 501 -0.017784 0.007362 3.139775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 495 503 0.019737 0.028227 -0.027252 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 498 505 -1.068580 -0.023265 0.036736 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 501 505 0.000798 -0.039487 3.130440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 458 506 1.017030 -0.993376 1.594010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 435 507 0.004803 -0.023700 -3.128455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 451 508 0.982187 0.007212 -0.020825 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 509 522 -0.999746 0.019901 -3.132435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 459 523 -0.012661 -0.008120 3.115410 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 435 523 -0.007475 0.009549 -1.552905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 450 523 1.023690 -0.006094 -3.135215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 490 523 0.983135 -0.010985 -3.140245 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 512 526 -1.002210 -0.967603 1.606720 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 521 526 -1.030310 -0.009681 -3.088680 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 521 528 -0.999602 0.005438 0.066296 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 460 531 -1.014030 0.037027 0.008811 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 507 531 -0.019190 0.002844 1.585800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 494 534 -0.011350 -0.000529 -0.025995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 501 534 1.010030 0.051645 0.010095 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 496 534 -0.030982 0.006331 -3.111830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 503 535 -0.034482 -0.034340 -0.008282 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 496 535 -1.068360 -0.024244 3.100315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 533 537 -0.010552 -0.040291 3.126170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 494 537 -0.974870 -0.017736 3.111880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 493 537 -0.010354 0.006845 3.134450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 433 539 1.988640 -0.012859 3.110910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 497 540 0.976100 0.010146 3.138845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 497 541 0.014543 0.005256 -3.097460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 505 541 0.005946 0.016573 -3.133920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 495 544 -0.000830 0.995550 1.586580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 515 546 0.009322 -1.044930 1.539480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 514 546 1.040390 -0.988948 1.546410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 515 547 0.008615 0.005698 1.571635 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 513 549 -0.013627 0.049293 3.136250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 509 550 2.016980 -0.993588 1.588010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 510 552 0.011643 0.020712 3.133160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 529 553 -0.029893 -0.024232 0.022308 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 499 554 0.083845 -0.990241 1.592300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 508 555 -0.995544 0.019893 3.136100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 522 556 0.013572 -0.021629 3.121345 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 525 557 0.028115 -0.014429 -0.023603 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 522 557 -0.999279 -0.011670 3.134965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 528 557 1.013240 0.024794 3.110145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 550 559 1.023750 -0.020812 -1.623200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 519 560 1.002010 -0.005677 -0.004874 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 511 560 -0.009388 0.968929 1.552850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 552 560 -1.044950 -1.006220 -1.579160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 566 584 0.009081 -0.009599 -3.125090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 568 584 0.046477 -0.003903 -0.026499 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 564 585 0.984490 0.013077 3.123125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 564 587 -1.012420 -0.041797 -3.133090 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 431 590 1.013850 0.006017 -3.125855 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 429 591 2.040970 -0.012908 3.112700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 431 591 0.035967 -0.013266 3.107580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 428 591 3.014053 -0.004317 -3.138010 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 430 592 0.972186 1.015790 1.548730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 567 598 -0.039344 0.975338 -1.585610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 567 599 0.022545 0.010318 -1.610260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 563 602 1.001940 0.021335 -3.106430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 572 604 -0.030720 -0.009624 0.018024 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 574 607 0.989025 0.031518 -0.058757 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 579 611 0.025850 -0.020853 0.001242 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 578 612 0.009426 0.017093 3.107585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 577 614 -1.011410 -0.024391 -3.133010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 613 617 -0.026076 0.012648 -3.136965 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 612 618 -0.001647 -0.009266 -3.124845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 578 619 0.979669 -0.003279 0.007891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 619 627 0.029965 0.043901 1.562650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 610 628 -0.031897 0.023449 3.114575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 578 629 -0.995522 -0.025263 -3.122790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 613 630 0.992401 -0.033880 0.011769 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 615 631 0.063646 -0.030134 -0.020910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 608 640 0.001548 -0.011526 -0.009964 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 616 641 1.016620 -0.014313 0.039032 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 609 641 -0.019654 0.025334 0.028851 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 576 644 2.004280 0.003516 3.119155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 627 644 0.008424 1.007994 1.575708 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 578 645 -1.010080 0.031985 -3.141510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 640 646 0.014239 0.018026 3.122035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 614 646 0.036679 -0.022750 -0.037140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 607 647 0.003535 -0.015555 -1.582250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 607 648 1.017260 0.006009 0.023016 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 633 648 -0.997450 -0.016374 0.015305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 623 655 0.041071 0.021009 1.602530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 623 656 0.014897 -0.993920 -1.582930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 653 658 -1.034730 0.012850 -3.113320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 651 660 1.032760 0.039650 -0.027768 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 665 669 -0.021003 -0.021045 3.135840 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 664 670 0.067768 -0.013012 3.138370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 664 671 -0.980827 0.033997 -3.122325 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 666 674 -0.002511 -0.021082 0.035039 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 667 676 -0.989834 0.017117 -3.115705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 664 678 0.022260 -0.040517 3.131980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 662 680 -0.026112 -0.042902 3.138720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 658 684 0.031811 0.029043 -3.122413 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 652 684 -0.009614 -0.027053 0.013532 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 656 685 1.033793 -0.014719 -3.131370 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 655 687 0.018253 0.026995 -0.000152 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 622 688 0.000251 0.020107 -3.105845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 621 689 -0.021750 -0.000838 3.127163 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 619 691 -0.018373 -0.031887 1.550100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 694 711 1.001550 0.035919 -3.119330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 693 711 2.012660 -0.024182 3.101135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 713 717 0.006171 -0.013412 3.139295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 713 718 -1.013030 -0.004366 3.132555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 710 719 0.985909 0.025175 1.573340 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 709 722 -0.981855 -0.031823 -3.110085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 707 722 0.010710 0.998126 -1.580830 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 720 726 -0.024670 -0.062485 3.139645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 710 726 -0.007337 0.045379 -0.049041 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 695 727 0.013910 -0.002738 3.115885 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 711 727 0.006007 0.003899 0.037772 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 712 727 -0.997679 -0.011281 1.605395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 697 729 -0.022366 -0.004741 0.033201 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 697 730 1.007330 -0.032581 0.001057 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 699 731 0.000384 -0.048050 0.004445 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 700 732 0.020865 -0.011260 0.043379 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 706 738 0.009854 -0.030865 -0.016373 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 705 738 1.015258 -0.009245 -0.013595 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 737 742 -1.000960 0.001167 3.110525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 703 743 0.008369 -0.052215 -1.572950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 735 744 -1.023100 -0.002482 3.140025 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 702 744 0.032898 0.004119 3.119655 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 698 748 0.985564 1.021700 1.594890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 732 748 0.005039 -0.018893 -0.010844 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 698 749 1.036120 2.039310 1.553330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 745 749 0.029773 0.016234 3.137560 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 743 751 -0.006410 -0.008019 1.576300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 742 751 1.014190 0.014098 1.636980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 736 751 -1.006160 -0.042015 -1.597560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 703 751 0.003096 -0.010105 0.023288 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 701 753 0.002495 0.024841 -3.093660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 733 754 -0.995960 0.017296 3.124585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 731 755 -0.026412 -0.004778 -1.564450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 700 755 -0.987260 -0.035771 3.105485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 732 755 -1.016050 0.019656 3.118645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 734 763 0.978254 -4.010060 0.021881 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 702 763 1.003810 -4.003500 -0.005932 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 760 764 1.989240 0.027000 3.133085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 761 765 0.019375 0.007551 -3.131020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 655 776 1.006900 0.002828 -0.026668 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 624 776 -0.997290 -0.957569 -1.541940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 731 779 -0.000548 0.010283 1.533590 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 731 780 0.948464 -0.016768 -0.043347 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 757 781 -0.030928 -0.042804 0.012557 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 758 782 0.004330 -0.034946 -0.035523 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 760 783 -1.001561 0.012876 -1.585483 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 758 783 1.036680 0.002881 0.012503 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 769 785 -0.017153 -0.026949 0.030975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 770 786 -0.032637 0.015194 -0.004236 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 817 821 -0.001648 0.010308 -3.126640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 816 821 0.994113 0.023868 -3.111000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 810 827 1.003210 -0.031120 -1.566695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 827 835 -0.013356 0.008003 -3.102330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 818 842 1.038220 1.022130 -1.564580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 820 851 -1.071580 -0.016206 -0.002801 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 818 852 0.020190 0.001069 -3.131920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 817 853 0.005550 -0.031309 3.093835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 827 858 -1.006050 0.021431 -0.047400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 827 859 -0.003938 -0.009849 -0.001123 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 827 860 -0.990392 0.010211 -3.136460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 856 864 0.011766 -0.005502 0.044951 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 836 866 -1.000490 -0.982164 1.567890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 813 868 -1.001710 -0.023440 0.032232 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 857 868 1.000760 0.022713 3.140295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 858 869 -1.018790 0.000845 3.115815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 855 871 -0.014450 0.003213 1.551690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 881 885 0.012058 0.001203 -3.140405 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 889 904 -1.029490 0.010446 -0.008966 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 894 904 0.001117 0.041681 3.141075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 907 923 0.027058 0.022846 -3.127365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 932 938 0.030597 0.022756 -3.113825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 921 949 0.001179 -0.034417 -3.113530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 928 951 -1.006520 0.003242 1.585830 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 947 963 -0.008250 0.010410 -0.000445 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 959 967 -0.017835 0.007191 -0.034101 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 961 968 -0.970797 -0.011331 0.019300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 959 968 -1.043003 -0.008281 3.138517 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 965 969 0.035436 0.000156 3.125600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 890 971 1.014600 -0.012291 1.553830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 888 974 0.010655 0.014183 3.130370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 977 981 -0.051609 0.005606 3.123655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 975 983 0.022242 -0.024609 -3.091300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 981 985 0.044670 -0.014918 3.116380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 977 985 -0.012591 -0.015957 0.006687 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 842 987 1.008160 0.019159 -3.140635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 850 988 -0.046996 0.015113 -3.136935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 847 1007 -0.018043 -0.023742 1.571410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1015 1023 0.001868 -0.017617 1.556495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1020 1024 2.003740 -0.036179 3.088930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1021 1025 0.015671 -0.006779 3.139842 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1019 1026 -0.988701 -0.053514 -0.011072 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1018 1026 0.010567 0.021887 0.015410 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1032 1036 3.024490 1.027470 1.567560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1034 1038 1.033360 3.029640 1.589480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1027 1041 1.981180 0.015541 -3.120060 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1037 1041 2.015490 1.999190 1.582675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1019 1044 -1.020790 -0.009833 3.114995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1024 1044 1.996350 -0.039356 -3.112050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1021 1044 -1.021870 0.009433 0.005283 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1017 1045 0.002770 -0.016487 3.114415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1021 1045 -0.017546 0.009544 0.011973 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1024 1046 -0.027407 -0.025632 3.129023 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1013 1050 -1.018820 -0.022003 3.126075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1051 1059 -0.000521 -0.003432 1.578200 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1057 1061 -0.019666 0.009576 3.124755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1056 1062 -0.014273 0.006326 -3.118750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1005 1068 -0.990890 -0.013084 0.019320 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1062 1071 1.034950 -0.051550 -1.578025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 847 1071 -0.000302 -0.049285 1.579550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1069 1073 -0.002108 -0.019552 3.134095 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1077 1081 -0.019651 0.015640 3.112895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 897 1085 0.024026 -0.053944 3.134295 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 880 1087 -1.007860 0.035889 -0.061929 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 897 1089 0.010096 -0.031598 0.019914 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 898 1089 -0.956383 -0.061318 -0.004869 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1084 1093 0.986714 0.008824 0.003662 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 895 1095 0.016448 -0.016240 1.573865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 982 1095 0.980299 -0.021796 -1.538590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 974 1095 0.990366 -0.018713 1.617665 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1089 1096 -0.983453 0.056343 0.059259 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1086 1097 -1.016860 0.020569 3.121310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1087 1111 -0.011134 -0.021994 -1.556285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 944 1119 -1.044400 0.004774 -1.588850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 876 1122 -0.992887 -0.986627 1.536520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 882 1123 1.002525 -0.048537 -1.587300 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 877 1125 -0.021025 -0.001406 0.005142 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1113 1125 -0.027992 -0.009511 3.120170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 983 1126 -0.004322 -0.971638 1.560380 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1112 1126 -0.031635 0.014086 -3.140995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1111 1127 -0.012630 -0.009780 -1.551510 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 903 1129 -2.007350 -0.072666 3.106340 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 902 1129 -1.020730 0.026359 -3.132115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1098 1129 -1.028140 0.003695 0.006023 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1093 1132 -1.013910 0.007061 -0.040901 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 902 1133 -0.970775 0.008462 -0.032925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1096 1134 -0.037481 -0.015975 -3.122980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 887 1134 0.986744 -0.001420 -3.130750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 902 1135 0.999984 -0.015282 -0.015161 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 880 1135 -0.994727 -0.011560 -0.030961 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1111 1135 0.006478 -0.009872 1.607255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 895 1135 -0.000746 0.002196 1.591725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 896 1137 1.000440 0.018750 0.000058 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1132 1137 0.986435 0.026172 -3.121935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1084 1139 -0.945698 0.021005 3.128200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1132 1140 -0.024701 -0.002171 0.022246 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1089 1141 -0.016079 0.003291 -3.122040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1128 1142 -0.016134 0.002495 -3.137470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 879 1143 -0.028623 -0.021561 -3.125360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1095 1143 0.031225 -0.043769 0.023599 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1097 1144 -0.989585 -0.046071 0.012323 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1134 1144 -0.049137 0.016264 3.123840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1084 1146 0.023296 -0.021173 3.130820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1074 1147 1.025200 0.020439 1.535740 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1066 1148 0.004199 0.005393 -3.130185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1068 1149 0.997411 0.019504 0.027890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1069 1149 0.020761 0.063190 0.014920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 847 1150 -0.008100 -1.007030 1.582030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 987 1153 0.025725 -2.003190 1.540755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 990 1153 -0.997761 -0.020090 -3.137610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 848 1153 0.980276 0.002024 -0.035886 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 852 1155 -1.000810 -0.013364 -0.010792 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 844 1156 -0.999494 -0.974175 -1.542780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 982 1161 -1.010580 0.016439 3.124180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 987 1163 0.011472 -0.029695 -0.033798 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 843 1163 -0.040108 -0.008086 -3.101615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 987 1164 0.988695 0.007812 0.026629 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1164 1172 0.029985 -0.028736 0.009202 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1154 1172 1.000790 -0.971220 -1.560875 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1166 1174 0.011036 -0.046500 0.018485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1168 1175 -0.955856 0.016113 3.095640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 807 1175 0.045491 -0.007390 3.139950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 811 1179 -0.021739 0.035658 -0.007300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1180 1187 -1.012720 -0.009862 -3.131300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 836 1188 -0.019854 -0.017590 -0.022893 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1178 1189 -0.979921 -0.029894 3.134070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1192 1197 0.972197 -0.020406 3.140945 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1178 1202 0.021771 -0.011313 -0.019594 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 811 1203 -0.012733 0.011015 0.042878 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 830 1205 -0.978576 -0.021355 -0.036196 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1181 1205 -0.016920 0.006314 -0.015976 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1183 1206 -1.015470 0.001259 0.026765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 832 1208 0.029627 -0.021253 -0.014852 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1181 1213 -0.004519 -0.014459 -0.003639 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1183 1214 -0.990834 0.053848 0.002936 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 831 1215 -0.010878 -0.027882 -0.008954 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1195 1218 0.007239 0.986384 -1.571430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 796 1226 -0.009047 0.028873 -3.133565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 789 1233 -0.004777 0.019591 -3.117905 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 785 1234 1.986970 1.030670 -1.549845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 772 1236 -0.023354 -0.015028 0.024998 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 772 1237 0.970780 0.008000 -0.004538 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 775 1237 -2.036000 0.031032 -0.028683 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 775 1238 -0.947644 -0.021795 -0.056694 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 775 1239 0.010750 0.001075 -0.022756 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 774 1239 0.981261 0.029157 0.013026 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 774 1240 -0.007580 0.016848 3.120115 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1237 1241 0.029213 0.001034 3.140155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 786 1243 0.966733 -0.014052 1.585070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 787 1245 2.017360 0.007072 0.034339 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 663 1247 0.037582 -0.015094 -1.582030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 671 1248 -0.015754 0.974989 1.558640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 651 1251 -0.014143 -0.030742 3.140250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 651 1252 1.023290 0.013386 0.016475 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 661 1253 -0.010955 -0.001937 0.024027 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1249 1254 -1.050960 -0.000731 -3.079310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 679 1255 -0.006776 0.025865 -1.569490 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 680 1255 -0.981029 0.024000 3.136435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 669 1257 -0.010148 -0.003697 3.134085 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1261 1265 0.001641 -0.005252 3.129900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1258 1267 0.971498 0.008290 -1.591625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 667 1268 0.037411 1.004100 1.585240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1259 1268 -0.016592 1.010240 1.552660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1264 1270 -0.016178 -0.003134 3.129365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1264 1272 -0.978396 1.037390 1.615575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1215 1279 -0.014723 0.010145 3.122643 134.164079 -0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 1207 1280 -0.027401 -0.956051 -1.558260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1182 1280 1.002450 -1.032060 -1.587260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1217 1282 1.008830 -0.006896 0.015975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1271 1286 1.037390 -0.026758 -3.121795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1272 1287 -0.964693 -0.006845 -1.557225 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1273 1289 -0.058998 0.021928 0.010700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1276 1291 -0.991162 0.037842 -1.567740 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1273 1293 -0.032681 -0.005307 3.098240 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1264 1295 -0.990973 0.015239 -1.554300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1286 1296 -0.016485 -0.004921 3.120965 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1217 1301 -0.005983 -0.032258 -3.135390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1217 1302 -1.038120 -0.039909 3.101625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1206 1303 1.001670 -0.004560 1.583595 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1278 1303 1.037570 0.009532 -1.556590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1207 1303 -0.024936 0.008567 1.577035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1182 1304 0.987968 -0.988998 -1.643370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1281 1305 -0.026439 -0.017545 -0.017064 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1218 1306 -0.013756 0.021505 -0.035685 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1282 1306 0.008403 -0.014387 -0.042747 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 804 1308 0.006634 0.008376 0.017031 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1196 1308 -0.002412 0.022516 -0.013945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1196 1309 0.995002 -0.028896 0.004175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1178 1312 -1.984020 0.004553 -0.011079 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 867 1315 -0.008877 -0.018438 1.512985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 836 1316 -0.022507 -0.031761 0.013540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1167 1319 -0.003555 -0.012873 -1.542910 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1309 1321 -0.007702 -0.006171 -3.130425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 805 1322 -0.984224 0.069062 3.110470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 803 1323 0.007683 0.028752 -1.577845 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1196 1323 -0.968214 0.019022 3.109130 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1197 1326 1.049530 0.021102 0.007191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 806 1327 1.021090 -0.018480 -0.027797 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1313 1329 0.024314 -0.003533 0.001289 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1177 1330 1.004640 -0.010983 -0.008566 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1316 1330 0.000953 -0.000381 -3.126510 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 835 1331 -0.000224 -0.026200 -1.573210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1187 1332 1.034440 -0.011640 0.023387 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 868 1332 -0.045684 0.052453 0.012420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 814 1333 -0.942263 0.008167 0.019368 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 866 1333 -0.978336 -0.018795 3.126235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 855 1335 -0.011241 -0.024757 1.591910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 871 1335 0.020562 -0.033361 0.034508 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 815 1336 0.011094 1.048210 1.586380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 854 1337 -0.988367 0.006024 3.127750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 817 1337 0.026266 0.018801 0.002882 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1155 1338 1.031210 0.029572 -3.128135 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 822 1341 -0.994650 -0.004765 -0.026121 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 822 1342 -0.012065 0.022868 -0.016897 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 855 1342 -0.992565 0.015256 -0.022629 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 870 1342 1.044060 1.013210 -1.585250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 856 1343 -0.997516 0.021188 1.557205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1336 1343 -0.992432 0.009429 -3.110040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 855 1343 0.024004 -0.015934 0.014188 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 874 1345 -0.993089 -0.000893 -0.026747 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 877 1349 0.015274 0.010068 -0.010129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1124 1349 0.988981 0.017990 -0.057958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 905 1353 0.020787 0.016743 -0.039155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 908 1354 -1.012360 1.001390 -1.561550 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 913 1356 1.010400 0.008842 -3.105905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1106 1357 -0.993092 -0.061505 -3.129835 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 1360 -0.970847 -0.021487 3.138770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1003 1363 0.016821 0.031104 -1.565985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1147 1363 0.003309 -0.031305 1.563710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1002 1365 -1.016180 0.001363 3.135540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1360 1376 0.015137 -0.012542 -0.024357 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1146 1379 0.979439 -0.010972 1.563730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1091 1380 -0.004020 -0.996511 -1.598730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1363 1380 -1.000390 -0.048948 -3.124960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1362 1380 -0.032901 -0.028841 -3.129760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 908 1386 -0.001703 -0.014144 -3.140300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 970 1387 0.985618 0.014480 -3.117440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 953 1390 -1.013930 0.010045 -3.124220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 919 1390 -0.972105 0.016994 -0.021038 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 927 1391 -0.003119 0.025694 -0.004587 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 971 1395 -0.008339 0.002661 1.588380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 953 1397 0.002788 -0.023497 3.114725 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 919 1399 -0.000666 0.014170 0.012535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 928 1400 -0.997991 -0.986739 -1.542675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 954 1403 1.007710 0.025757 0.009509 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1401 1405 -0.008950 -0.000108 -3.135550 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 949 1405 -0.034988 0.000712 0.058965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 919 1407 -0.015707 0.036337 -0.004009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1409 1413 -0.000067 0.004377 -3.119730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1391 1414 0.006505 1.001870 -1.570960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1401 1415 -2.032420 -0.047270 1.582635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 914 1419 1.020620 0.021201 -1.552545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1388 1419 -0.971843 0.027535 3.118740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1106 1419 0.993448 0.009715 -1.575595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1396 1420 -0.009565 -0.018367 -0.018125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1390 1421 -0.962255 -0.038758 0.024557 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 918 1422 -0.017523 0.018860 -0.014129 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 926 1424 1.009420 1.019830 1.569990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1409 1425 0.016458 0.001345 -0.017417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1409 1426 0.959210 0.007808 -0.002485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1412 1426 -0.041282 0.023866 -3.121445 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1411 1426 -0.976888 0.001810 -0.016300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1411 1427 -0.023367 -0.014826 0.021111 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 919 1437 2.010350 0.000567 3.116770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 928 1439 -1.015530 -0.039143 -1.600045 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 929 1440 -0.957272 -0.000966 -0.034404 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 938 1444 0.005560 0.007720 3.136655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 933 1445 -0.027362 -0.009613 0.052970 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 935 1446 -0.998082 -0.038664 0.007735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 936 1446 -0.003381 -0.055755 3.134885 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 935 1447 0.002132 -0.025125 0.018065 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 933 1448 0.985889 -0.005992 3.112130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1445 1449 -0.002047 -0.006760 -3.138875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 930 1451 1.032270 0.004585 -1.580905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 939 1451 0.012372 0.014449 -0.001663 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 967 1455 0.040848 -0.008869 -1.590555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 959 1455 -0.005892 -0.017892 -1.560795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 961 1457 0.000524 0.025833 -0.007887 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 946 1458 -0.008323 -0.029720 0.037818 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 963 1459 -0.007944 0.038257 0.002567 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 891 1460 -0.975070 0.018133 -3.108365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1109 1462 1.023030 0.000942 -0.035671 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 888 1463 -0.981693 0.010219 -3.137165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 880 1463 -1.009390 0.000979 -1.585565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1111 1463 0.035318 0.011228 0.029374 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 896 1464 0.000673 0.024919 0.002994 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 878 1464 2.064300 0.005987 -0.014810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 901 1466 -1.012950 0.003785 3.127560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1075 1467 -0.016365 -0.014501 1.567760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1005 1469 -0.040447 0.017503 -0.013990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1152 1470 -1.046610 1.001520 -1.598285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1054 1470 1.002910 0.978320 -1.589355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1149 1470 1.001490 0.041992 0.038867 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1055 1470 -0.047496 1.007400 -1.551985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 846 1471 1.003500 0.012958 1.603770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1056 1472 0.027253 0.037000 0.006781 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1058 1476 0.018769 -0.030901 -3.135300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1011 1476 -1.006840 0.028142 3.130555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1473 1478 -0.996022 -0.024361 -3.117260 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1062 1478 0.025481 0.027570 0.019524 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1470 1479 1.023730 -0.035430 1.559745 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 848 1480 -0.985273 1.028870 1.587060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1470 1480 -0.002240 -0.003483 -3.131670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 992 1481 0.980649 0.020231 0.020108 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1082 1481 -0.977920 -0.019068 0.004754 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1004 1482 -0.020949 -0.044074 3.125225 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1131 1483 0.028117 -0.036847 -1.572610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1505 1509 0.000155 0.050299 3.141360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1505 1510 -0.991965 -0.032306 3.114150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1500 1514 0.015825 -0.028283 -3.136960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1507 1515 -0.000540 -0.006703 -0.004290 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1500 1524 -0.011590 -0.051042 -0.016619 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1512 1528 0.020936 -0.007061 0.043079 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1500 1532 -0.012099 0.006710 -0.010198 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1525 1533 0.041699 -0.010673 0.016086 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1513 1533 -0.024474 -0.006472 -3.134365 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1529 1533 0.005821 -0.011900 3.132720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1528 1534 -0.012859 0.002395 3.118700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1542 1546 -2.032920 -0.028263 3.135115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1538 1546 -0.001153 -0.021043 -0.023923 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1540 1549 1.008890 -0.024279 0.002717 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1544 1549 0.965491 0.010821 -3.136575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1535 1550 0.002453 -0.980158 1.586850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1529 1552 -0.941811 0.021549 -0.005524 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1507 1555 -0.007828 -0.028038 -0.003580 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1508 1555 -1.012000 0.000204 3.132495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1496 1558 0.025541 0.053880 -3.093145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1496 1560 0.023704 -0.030335 0.005603 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1523 1562 1.006470 0.011965 3.111425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1568 1572 1.990730 0.009975 -3.136385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1569 1573 0.025277 0.023721 -3.126355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1568 1574 -0.014423 0.025781 -3.132505 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1570 1574 -2.026450 -0.007319 -3.136293 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1566 1577 -0.971582 -0.004600 -3.135915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1507 1578 1.003880 -0.008241 -3.103985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1564 1578 -0.029500 -0.008489 -3.119345 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1564 1580 -0.988524 -1.021170 -1.566155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1495 1581 0.025544 -2.032980 1.583580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1557 1581 0.027473 -0.000452 -0.006917 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1492 1586 0.008252 -0.049927 3.137675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1489 1589 -0.027788 0.001956 -3.120685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1368 1590 -0.009307 0.018705 3.131660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1488 1590 -0.053957 -0.030098 -3.121725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1000 1592 -0.011904 0.020104 -0.011637 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1379 1594 0.048802 -0.971424 1.563545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1084 1595 -0.972193 -0.011245 -0.030071 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1076 1595 -0.983261 0.030496 1.571765 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1378 1597 -0.973792 0.007344 3.139115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 1598 -0.975311 -0.017606 -0.012690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1359 1599 0.046216 0.031624 -1.570550 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1373 1601 -0.012112 -0.067906 3.135930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1372 1601 1.012910 -0.042876 3.135890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1373 1602 -1.000450 0.017167 -3.102685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1491 1603 0.023012 -0.022073 1.579190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1488 1606 0.019637 0.003979 3.138220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1592 1608 0.006513 -0.000707 -0.038155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1466 1611 0.984007 -0.012913 -3.134200 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1075 1611 0.010400 0.037361 -1.595080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1066 1612 1.020390 0.997410 1.552440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 996 1613 0.983380 0.000636 -0.023703 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1366 1613 -0.993432 0.000518 0.003237 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1366 1614 0.020801 0.012757 -0.004389 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1001 1614 -0.991497 0.024104 -3.107585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1590 1617 -0.981579 -0.033086 3.132635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1372 1618 -0.991939 -0.986357 1.556380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1372 1619 -1.025570 -0.030801 1.584400 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1369 1621 0.017493 -0.010244 -3.137165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1489 1622 -0.994764 -0.007718 -3.138595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1615 1623 0.024768 -0.010594 1.574450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1591 1624 0.001830 -1.014820 -1.589140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1367 1624 1.013600 0.004116 0.037951 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1559 1631 0.035237 -0.002678 -3.112750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1494 1631 1.002450 0.001731 -1.602120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1585 1633 0.011301 -0.025397 0.020483 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1493 1633 -0.005749 -0.062755 -3.120920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 1634 -0.003209 0.979348 -1.593440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1585 1637 -0.008394 -0.031025 -3.119865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1632 1639 -1.023040 -0.003523 3.095510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1559 1639 0.026885 -0.023757 -1.576140 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1630 1639 1.000750 0.008475 1.557200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1630 1640 0.001940 -0.006708 3.136850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1627 1642 -0.011797 -0.994328 1.575933 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 1628 1642 0.025183 0.033985 3.112270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1629 1642 -0.978706 -0.036212 -3.131915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1626 1643 0.990189 0.000271 1.569480 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1626 1644 -0.015220 0.045989 -3.114640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1627 1644 -1.012120 0.039252 3.119845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1625 1645 0.033938 -0.008808 -3.133770 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1603 1651 0.013848 -0.034857 -1.546210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 1652 -0.025692 -0.986771 -1.590490 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1603 1652 -1.003100 0.010293 -3.122030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 1653 0.010397 -2.022490 -1.542150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1373 1653 0.003640 -0.009320 -0.008605 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1600 1654 0.020990 0.029391 3.137465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1376 1654 -1.021260 -0.995576 1.513335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1358 1656 1.028080 -1.008060 -1.582500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1428 1660 0.038871 -0.017573 -0.023085 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1430 1661 -0.971578 -0.038387 0.024454 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1430 1662 -0.005980 0.006865 -0.011096 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1433 1665 -0.009442 0.006266 0.018467 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1433 1666 0.964713 0.001310 0.000771 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1432 1666 1.991050 -0.039276 -0.014389 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1433 1668 1.020710 0.007327 -3.122595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1432 1670 -0.016755 0.013415 3.124450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1433 1670 -1.015960 0.057237 3.112800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1662 1670 1.005630 -0.973967 1.564770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1663 1671 0.016092 0.022554 1.564480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1430 1672 -0.052025 0.019916 3.121510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1660 1675 -1.028090 -0.014326 3.117130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1567 1679 0.052961 -0.026592 -3.115755 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1491 1683 -0.030614 -0.012981 3.129030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1602 1684 0.016507 0.045327 -3.112080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1653 1685 0.006870 -0.000258 0.031270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1374 1686 -0.026712 0.042490 -0.005726 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1600 1686 0.011316 -0.025326 3.141555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1654 1687 1.006180 -0.044340 -0.012585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1131 1690 -0.050590 -1.035890 1.602700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1484 1691 -0.964523 -0.009951 1.557540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1075 1692 -0.002661 -0.989145 -1.549620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1094 1694 -0.010222 0.021632 0.001399 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 887 1694 1.013720 -0.005597 -3.119610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1351 1695 0.048750 0.008216 3.103895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1160 1696 -0.015311 -0.020983 -0.038585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1351 1696 -0.015105 0.980480 1.581130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 977 1697 -0.019061 0.018685 0.000575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 978 1698 0.015530 -0.012458 0.002859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1156 1698 -0.042967 -0.016443 -3.114985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 851 1699 -0.011377 0.021452 -1.496935 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1170 1699 1.014280 -0.006191 -3.118555 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1164 1700 -0.037099 -0.007389 0.047216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1169 1701 -0.012276 0.029744 3.096060 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1170 1701 -0.990542 -0.018269 3.136730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1173 1701 0.034222 -0.012592 -0.022967 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1168 1702 -0.028731 0.030607 -3.117455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 807 1702 1.025570 -0.012849 -3.125895 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1175 1702 -0.994863 -0.000769 0.005720 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 840 1703 -0.983693 -0.004853 3.139940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 837 1704 0.996581 0.006810 -3.132350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1189 1705 0.042166 0.030493 -3.138490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 860 1707 -0.996410 -0.005489 -1.581380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 837 1710 1.017470 0.025187 0.017294 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1190 1710 0.006273 0.046213 0.003732 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1703 1711 -0.019539 -0.033384 -1.580360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1327 1711 -0.029829 0.029701 1.561290 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1056 1718 -1.041180 0.988114 -1.572020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1006 1720 1.975410 0.003716 -0.010427 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1716 1722 -0.001014 0.027962 3.120052 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1024 1727 -1.040230 0.009598 -0.015141 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1013 1729 -0.029393 0.000872 -3.113660 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1011 1731 0.043012 0.007343 -1.564690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1049 1734 -1.035850 -0.028953 -3.119015 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1725 1737 -0.020751 -0.028487 3.135365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1715 1738 1.003940 -0.007055 -3.135960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1712 1741 1.035500 -0.021092 3.103335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 839 1742 1.014310 0.020438 -3.115210 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1198 1742 0.973530 1.000020 -1.554890 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1310 1743 1.017990 -0.016884 -1.581440 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 839 1743 -0.008209 -0.005486 3.128205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1198 1744 -0.007360 0.002631 -3.136865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 805 1745 0.004753 -0.028478 -3.113385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 804 1746 -0.004237 0.007754 -3.122745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1307 1747 0.017794 -0.000484 1.580230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1272 1749 -1.033530 1.980510 -1.560095 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1272 1750 -1.008850 1.012100 -1.546275 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1229 1755 -2.007400 0.004205 0.005505 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1226 1756 0.028176 -0.009283 3.116275 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 803 1762 -1.014130 -0.002741 -0.006678 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 802 1762 -0.011211 0.037664 0.028177 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1299 1763 0.048254 -0.012087 -1.582510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1284 1763 -0.950508 -0.018423 1.566785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1325 1765 -0.039045 0.051128 -0.010390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1192 1766 0.026850 0.017396 -3.127690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1705 1770 0.992140 0.005837 -0.017106 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 810 1772 -0.019509 0.014623 3.139470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1709 1773 -0.032537 -0.009563 0.045199 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 840 1776 -0.008991 -0.014097 -0.032704 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1742 1776 0.984850 1.019260 1.560660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1701 1777 -0.018148 -0.007704 3.116505 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 838 1777 0.951290 -1.988010 -1.592060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 842 1778 0.007338 0.047519 -0.002960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 818 1778 0.998344 0.985718 -1.583930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1162 1779 1.033060 -0.012264 -3.123210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 820 1779 -0.983202 -0.000695 1.604970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1339 1779 -0.014567 0.020591 -1.582770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 848 1782 -0.020090 -0.002671 -3.133355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1471 1784 -0.989961 0.007265 -3.136888 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1362 1786 2.009140 0.032795 3.134775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1139 1787 0.001433 -0.008966 -1.582950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1612 1788 0.022436 0.018928 0.032957 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1001 1789 -0.019302 0.015147 3.119840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1484 1789 0.981733 -0.005129 -0.006740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1486 1790 0.028622 -0.005728 0.019386 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1591 1791 0.006511 0.018026 -1.598180 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1614 1792 -0.024319 0.021626 3.130175 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1488 1792 -0.992041 -0.998031 -1.570370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1000 1792 0.006321 -0.014589 0.037216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 997 1793 -0.016293 0.008335 3.097585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1003 1795 0.009315 0.016001 0.018596 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1129 1795 2.019390 -0.027331 -3.126820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1365 1798 0.977791 -0.017884 0.001811 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1614 1798 -0.018596 -0.005947 -0.035122 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1487 1799 -0.013280 -0.007277 0.005592 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1591 1799 -0.000208 -0.001249 -1.592353 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1052 1804 -0.000634 0.007816 0.000085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1053 1804 -1.015010 0.015333 0.004901 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1008 1805 0.969076 0.025093 -3.131020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1716 1810 0.018755 -0.030424 -3.138745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1722 1810 -0.016904 0.023981 0.000435 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1737 1810 1.996260 1.030150 -1.584675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1716 1811 -0.977985 0.017115 3.100630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 799 1814 1.002580 0.011122 -3.129945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1759 1815 0.038160 0.001372 3.120710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1816 1821 0.996607 -0.019422 3.123305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1758 1822 1.039130 1.023740 -1.573930 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1758 1824 -0.001172 -0.039715 3.136992 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1224 1825 0.971458 0.035688 0.004613 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1822 1830 1.026290 -0.998340 1.528320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1223 1831 -0.043423 -0.017946 -1.601120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1819 1834 -0.999430 -0.033842 0.011638 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1819 1835 -0.010830 -0.004956 0.036170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1264 1846 -0.980093 -1.029550 1.561805 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1271 1846 0.006543 0.984734 -1.575670 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1296 1847 -0.980522 0.047472 -1.575800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1265 1849 0.007324 0.030923 -0.017106 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 667 1851 0.017787 0.033783 -1.585615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 666 1851 1.000860 -0.006682 -1.582015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1267 1851 0.014751 -0.031739 -0.011113 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1259 1852 0.987388 0.032652 0.028625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1856 1861 1.001410 0.018451 -3.121630 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1857 1861 0.007755 0.019954 3.128915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1855 1864 -0.980483 -0.000596 -3.120965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1859 1864 -4.047550 -0.989426 -1.535860 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1853 1864 1.009570 -0.050749 3.086350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1854 1864 0.017373 -0.000680 3.121935 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1856 1864 -0.982531 -0.985014 -1.598860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1852 1865 0.998403 0.000784 -3.094695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1853 1866 -1.012020 -0.054794 3.118600 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1851 1868 1.010120 -0.041438 -0.009668 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1259 1869 0.025435 -2.001580 -1.574875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 659 1873 2.006550 0.051249 3.128830 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 634 1874 0.976091 -0.987714 1.601180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 683 1875 -0.003206 0.009378 -1.565670 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 637 1877 -0.015217 -0.005695 0.002504 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 633 1877 0.004996 0.008405 3.124640 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 608 1878 -0.991811 -1.001350 1.605670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 615 1879 0.023068 0.034923 -1.557195 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 648 1886 -1.014960 -1.045130 1.568450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 615 1888 -0.043234 -0.979152 -1.572965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 563 1891 -0.018918 0.002471 1.577710 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 562 1891 0.976611 -0.000758 1.529380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 603 1892 -1.005620 0.007646 -3.127265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 567 1894 -1.029700 -0.026622 0.008678 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 599 1895 -0.009313 0.022371 1.523150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 581 1896 0.995625 -0.045115 3.117785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 580 1897 1.037560 0.042838 3.107255 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 581 1897 0.011062 0.012406 3.097205 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 580 1898 0.007767 -0.000761 -3.128470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 693 1899 -2.027630 0.019342 -1.612210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 567 1904 1.006840 0.027757 -0.011816 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 582 1904 0.992929 -1.006630 -1.558560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 714 1907 0.983808 -0.015309 -1.567970 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 716 1907 -1.015100 -0.004468 1.640850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 714 1908 2.021470 -0.021243 -0.001191 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 415 1909 2.037950 -0.014452 -3.102115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 414 1911 1.009303 0.021084 3.117369 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 1909 1913 2.001330 2.000770 1.541695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 595 1914 0.986292 0.004597 -3.111600 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 594 1914 2.011210 0.039655 3.138345 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 594 1915 0.956900 -0.009452 -3.074740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 595 1916 0.027690 -0.969365 -1.580710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 596 1916 -0.026175 -0.039141 -0.007859 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 597 1917 -0.013807 0.001487 -0.018932 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 598 1917 -1.013653 0.012266 0.016738 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 600 1919 -0.981792 0.016899 1.580170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 598 1919 0.988610 0.028227 -0.021158 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 563 1923 -0.021495 -0.018837 3.133623 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 572 1924 -0.030230 0.020506 -0.008013 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1889 1926 -1.001200 0.022634 -3.116060 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 607 1926 -0.994124 -0.052017 0.000235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 638 1927 0.973856 0.037990 -3.141250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1887 1927 0.007841 0.015599 -1.566590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 639 1927 -0.004398 0.009334 3.122035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 647 1928 0.986739 0.013357 -0.011463 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1886 1928 0.003117 -0.016517 -3.112650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1881 1928 -0.956658 -0.001364 -0.008554 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1884 1929 0.976082 -0.019474 -3.112740 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1881 1929 0.027876 -0.006818 -0.008048 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1884 1931 -0.997972 -0.004057 3.125515 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 519 1935 -0.020380 0.008875 1.582520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 550 1935 1.060820 0.030482 1.567520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 559 1936 1.005770 -0.029426 -0.007699 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1933 1937 0.037638 -0.000073 3.118305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1932 1937 1.001354 0.007475 -3.132450 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1932 1938 -0.020102 -0.022084 3.119690 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1883 1938 -0.001480 -0.999908 1.560250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1883 1939 0.050230 0.005542 1.589130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1871 1941 1.974070 0.002981 -3.128300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1872 1942 -1.009578 1.014417 -1.565750 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1871 1942 1.031780 -0.002135 -3.130770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1868 1946 -0.035733 -0.018844 -3.130980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 675 1947 0.048119 0.008014 1.572150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1267 1947 0.046182 -0.020423 -3.140580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1259 1948 -1.021840 -0.011865 -3.134165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 674 1948 -0.002307 0.008866 -3.121745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1867 1948 0.960130 -0.004011 -0.020799 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 662 1949 1.040570 -1.989190 1.539390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 664 1950 -0.017560 0.000987 -3.124393 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 673 1950 -1.007390 -0.008573 -3.111215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 680 1951 -1.015550 -0.012440 -1.572200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 671 1952 -0.040135 -1.067720 -1.574040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1754 1953 1.023490 1.960920 -1.569370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1227 1953 2.038220 -0.006269 -3.130110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 679 1953 -0.044334 -2.003110 -1.575140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1828 1955 -1.008380 0.026738 -0.035567 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1838 1959 0.960079 0.022115 -1.572110 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 789 1961 -0.028623 0.026898 3.114540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 790 1966 -0.040145 0.007678 -0.006063 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 789 1966 1.010740 0.048194 -0.054706 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1839 1967 -0.003271 -0.018728 -3.133600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1827 1971 -0.037287 0.048466 1.576085 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1756 1971 -1.000480 0.001534 -1.575730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1955 1971 0.020325 0.005030 -1.614550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1226 1971 0.940694 0.002506 1.547165 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1228 1972 -0.011532 -0.032134 -0.007826 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1841 1973 -0.027176 0.000495 -3.128055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 793 1973 0.010023 -0.024635 -3.138215 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1838 1975 0.993292 0.007587 -1.528380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1232 1976 -0.051791 -0.021885 0.000456 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 771 1978 -0.019719 1.014230 -1.575585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 771 1979 -0.000206 0.003485 -1.559933 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 770 1980 0.058967 0.020185 3.130490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1242 1980 1.013800 0.969365 1.554880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 767 1983 0.006000 0.036361 -3.085918 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 766 1984 1.024110 0.980924 1.589390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1835 1991 3.956960 -0.096783 -1.550680 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1988 1993 0.993837 0.011343 3.139400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1988 1994 0.035207 0.015742 3.129900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1989 1994 -0.970148 -0.027328 3.118190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1990 1994 -1.996790 -0.020248 3.084490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1987 1994 1.001550 0.000319 -3.137785 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1988 1996 -0.971028 -0.973356 -1.572890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1987 1996 -0.052882 -1.019580 -1.555300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1230 2000 0.021388 0.014343 -3.137585 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1755 2002 0.992975 0.000187 -3.130690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1955 2003 0.004573 -0.006991 -1.579060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1968 2005 1.010680 -0.026294 3.129780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1230 2005 -0.991952 0.017318 0.018744 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2000 2006 -0.020501 0.003673 3.120540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1840 2006 0.020880 0.017827 -3.081055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 790 2007 1.021550 -0.033538 1.551960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 794 2010 -0.017384 0.031931 0.015663 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1970 2010 0.001508 -0.005808 -0.014449 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1968 2014 -0.008449 0.004160 -3.123145 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 792 2014 -0.019009 -0.027456 3.130390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1837 2016 1.001800 -0.001429 -3.117370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1820 2020 -0.009990 -0.012339 0.003551 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1224 2022 -0.980207 -1.027030 1.579925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 799 2022 -0.016362 1.025830 -1.555440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1831 2023 -0.035729 0.006079 -1.589810 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1759 2023 0.032661 0.003237 -1.578960 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1739 2026 -0.030014 -1.007380 1.571820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1715 2028 -0.019867 1.040800 1.574510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1714 2028 0.977572 0.963022 1.518670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1812 2028 -0.007393 0.000826 0.002051 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1823 2030 0.026544 1.000880 -1.583265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2023 2030 0.015186 1.021570 -1.595935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1759 2030 0.988558 -0.010733 -3.105145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1832 2030 -0.982808 -0.995503 1.560750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1831 2031 0.029073 -0.031806 3.140480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1820 2035 -1.000310 -0.018609 -3.115755 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2016 2038 0.020347 0.010353 3.120500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2007 2039 -0.010566 0.004154 1.560990 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1974 2039 1.022580 0.010607 1.608930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 792 2039 -0.975663 0.006343 -1.551315 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1958 2039 1.056480 0.025081 1.575400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1837 2040 0.998594 -0.004310 3.109215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1838 2041 -1.021900 -0.018406 3.139065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1837 2041 -0.035368 -0.037845 -3.130270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1836 2043 -1.005910 0.010857 3.135315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1836 2044 -1.013990 0.961023 1.564455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2034 2044 -0.012104 -0.011055 3.140135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1818 2045 -0.984814 0.026111 3.125265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2022 2047 0.992697 0.005019 -0.010939 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2024 2047 -0.999838 -0.008773 -1.572740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1815 2048 -0.015699 -0.993257 -1.569300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2023 2048 -0.971493 0.005466 3.126930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2044 2050 0.005256 0.015895 3.128460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2020 2050 -0.047345 -0.015828 3.128840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1736 2054 -0.980549 -1.007630 1.588300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1727 2055 -0.024263 -0.005480 -1.585190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2053 2057 0.006377 -0.025482 3.122440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1835 2058 -0.035744 -1.004010 1.582040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2035 2059 0.014187 0.011625 1.538520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1819 2060 -0.013295 -0.979249 -1.573330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2053 2060 -1.022890 0.000143 0.026283 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2057 2061 -0.010022 -0.013338 -3.136700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1016 2063 -0.999666 -0.001139 -1.547250 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1726 2064 0.021772 0.002078 -3.125093 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1737 2069 0.005663 0.015579 -3.101135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2055 2070 0.019740 -0.989890 1.515270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1736 2070 0.010108 0.003604 -3.111445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1022 2070 1.980760 -0.004949 3.124550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1733 2072 0.990775 -0.040962 -3.137600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1734 2072 -0.021742 0.028397 -3.104730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1729 2073 -0.000967 0.003654 0.002273 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1049 2073 -0.000849 -0.004014 0.006870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1050 2074 0.002857 0.032945 -0.017860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1475 2075 0.029878 -0.001665 -1.552610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1031 2079 0.009979 0.055373 1.588320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1030 2079 1.009520 0.011356 1.562060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1044 2082 -1.031240 0.982312 -1.568515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1041 2083 1.982530 -0.017594 -1.543015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1028 2083 -0.982685 -0.032865 3.120560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1028 2084 0.003589 0.008715 -0.000311 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1030 2085 -0.999539 -0.051019 0.028597 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2081 2085 -0.017713 -0.039781 3.141345 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1031 2086 -1.003710 0.017349 0.006442 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2084 2089 0.984522 0.004276 3.130100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2082 2089 -1.010130 0.022459 0.034848 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2084 2090 0.006448 -0.001773 3.129480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1043 2091 -0.027313 0.016901 -1.558645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2082 2092 -0.019945 0.021159 -3.134010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1028 2093 0.988746 0.000541 0.009820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1029 2093 -0.025729 0.011497 0.038282 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2077 2097 0.032377 0.014382 -3.128630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2076 2099 -1.009020 0.035205 -3.128770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1011 2099 0.002509 -0.027450 3.133745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 991 2101 1.990100 -0.009981 -3.141370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1055 2102 -0.991817 -0.000657 0.019004 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1720 2102 -1.006060 -0.974040 1.580155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1805 2102 1.008920 -0.000563 -0.002888 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1054 2102 -0.014287 -0.013171 0.010133 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 847 2103 0.014441 -0.012173 3.125535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1720 2103 -0.985811 0.015028 1.561225 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1061 2104 1.015760 0.038414 -3.102135 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1472 2104 0.035089 0.020479 -0.009218 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1057 2105 0.001901 -0.003796 -0.019251 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1802 2106 1.023310 1.008000 -1.604590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1011 2107 -0.014657 -0.002713 -0.032330 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2075 2107 0.020549 0.005609 1.527360 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1051 2108 -0.016169 -1.029060 -1.601820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1805 2108 -0.978229 -0.036966 0.005352 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1476 2109 0.978129 0.016480 0.039009 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1719 2110 0.003659 0.998157 -1.557630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1079 2110 -0.020833 -1.029280 1.585265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1783 2111 -0.004405 0.023406 -3.137860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 993 2112 -1.035330 0.010768 0.035007 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1074 2115 1.020840 0.016380 -0.020692 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1098 2116 0.963011 0.982869 1.599180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1481 2117 -0.014016 0.009582 3.126020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1471 2119 -0.025314 -0.023398 0.025512 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1719 2119 -0.030692 -0.007780 -3.102525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1152 2119 -0.978982 -0.038834 -1.588695 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2110 2120 1.023630 1.001610 1.551170 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1807 2120 0.019001 1.017700 1.613380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2112 2120 0.009490 0.001713 -0.030464 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1719 2120 0.934411 0.023671 0.010342 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1076 2121 1.013940 -0.018180 -3.117540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1469 2121 -0.008287 -0.024472 -3.106410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1787 2123 -0.014550 -0.005549 -0.012197 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1794 2124 2.013550 -0.028764 0.000774 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1134 2126 0.027625 -0.006017 0.016056 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 984 2127 -0.976713 -0.000776 1.588435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1135 2127 0.036444 0.012461 -0.004322 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 984 2129 1.061020 -0.025876 0.007571 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1171 2131 0.013997 -0.010630 3.094720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1780 2131 -1.002270 -0.029974 1.582710 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 982 2133 -1.022520 -0.024845 0.046230 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 979 2133 -2.021720 -0.013441 -3.084490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1135 2134 -0.012957 -1.006890 1.581040 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1463 2136 -0.976299 -0.032576 -3.104990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1352 2136 0.021523 -0.026127 -0.011618 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 972 2137 0.999856 -0.008931 3.131765 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1135 2137 -0.008707 1.993330 1.580040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 962 2139 1.027850 0.042713 -1.593050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 969 2139 1.964380 -0.026309 -1.569490 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 947 2140 0.989420 0.010341 -0.047809 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1382 2142 1.012110 -1.011040 1.572470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1068 2147 -1.000130 -0.023585 0.008859 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 2151 0.018169 0.041636 0.021863 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 2152 0.025865 -1.017300 -1.573310 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 910 2152 -0.000712 0.005106 3.120055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 913 2152 -0.985691 0.037168 -0.035619 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1107 2155 0.002214 0.007085 0.022056 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1402 2156 -0.018542 -0.012004 3.135135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 926 2158 0.013886 0.018801 -0.003023 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1407 2159 -0.000160 -0.008063 0.016855 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1422 2159 0.977617 -0.026915 -0.035511 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 926 2160 0.010085 -0.007144 3.089540 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1416 2160 0.017048 0.015657 0.010925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 907 2162 1.006900 0.035542 3.140290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 923 2163 0.004838 0.039354 -0.007950 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1356 2163 -0.981788 0.009758 1.576850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1403 2164 -0.000509 -0.998203 -1.593910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1459 2164 1.007720 -0.002926 -0.010185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2142 2166 0.018794 0.020632 0.020896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1360 2167 -1.015490 -0.004566 -1.608980 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 908 2169 1.045560 0.030195 -3.131040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2140 2169 0.977292 0.017856 3.136765 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2153 2169 -0.040625 -0.004112 0.013046 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1104 2169 1.003690 -0.015631 0.003601 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 973 2170 -1.975850 -1.020320 1.543905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1396 2171 -0.964162 0.001359 -1.613620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1397 2172 -0.979919 -0.039979 -0.001721 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 953 2173 -0.013592 0.002680 -3.106470 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 926 2174 -0.006753 -0.015450 -0.030118 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1398 2174 -0.046016 0.009202 -0.014998 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2160 2174 0.013099 0.019870 3.136955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1414 2175 0.975627 0.012608 1.538490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1409 2177 -0.038026 -0.032824 0.027522 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1425 2177 -0.029678 0.028579 -0.030363 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1426 2178 -0.009886 -0.006080 0.016995 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1410 2179 0.996063 0.014155 -0.028013 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1658 2180 0.027671 0.037775 3.116520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2168 2181 -0.971254 2.032890 -1.556365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2143 2182 0.008460 -1.001880 1.560340 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1103 2184 1.011250 -0.000019 0.008700 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1657 2185 -0.010289 0.004310 -0.019732 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1657 2186 1.031004 0.021220 -0.011556 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1658 2186 0.029193 0.012672 -0.026376 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1412 2187 -0.948609 -0.013068 1.534370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1676 2188 -0.033829 0.008398 0.011837 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1577 2191 -1.973630 -0.005125 -0.017417 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1427 2194 1.023550 0.005585 -3.105020 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2179 2194 0.990726 0.025666 -3.117960 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1659 2196 -0.042989 0.997669 1.573580 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2189 2196 -0.989769 0.034106 -0.004799 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1677 2197 0.009754 -0.008643 0.012127 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2192 2197 1.029620 0.009140 3.122290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1574 2198 1.011470 1.013850 -1.607030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1679 2199 0.010308 0.014343 -0.025798 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2190 2199 0.970799 -0.026625 -0.027732 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2191 2200 0.012586 1.022400 1.565330 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 2202 0.931324 0.035435 3.123290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1491 2202 1.012270 0.009587 -3.132415 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1619 2203 -0.000030 -0.035834 -3.126135 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2200 2209 0.989312 0.035075 0.040415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1587 2209 0.009050 2.006930 -1.565645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1683 2209 -2.031510 0.017061 0.005197 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2202 2210 0.012884 0.024700 -0.022172 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 1682 2210 0.027735 -0.031366 0.004647 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1634 2211 1.003710 -0.023912 -1.566435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1587 2211 0.028232 -0.002171 -1.525845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1634 2212 -0.017978 -0.003685 -3.109785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1584 2214 0.013162 -0.024312 -3.136605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1495 2215 -0.010388 -0.031735 -0.013919 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1581 2217 -0.012550 -0.001886 -3.138050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1556 2217 1.005350 0.022388 -3.124760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1562 2220 0.003903 -0.018329 3.104620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1580 2220 0.003655 -0.019290 -0.014958 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1560 2222 0.047554 0.042555 3.138620 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1558 2224 -0.007749 -0.001892 -3.140370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1497 2224 -1.000120 -0.021023 -0.016386 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1556 2226 -0.011844 0.008880 3.136565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1565 2227 -2.025470 -0.019142 1.539390 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1555 2228 -0.048534 0.974767 1.569450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1523 2228 -0.982840 -0.007711 3.138115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1506 2228 1.017910 0.970605 1.569850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1517 2229 -0.007094 -0.037405 0.013000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1518 2230 -0.018791 -0.029518 -0.036338 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1520 2230 0.018172 0.018870 -3.120710 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1518 2231 0.998833 -0.021549 0.012742 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1545 2236 0.983896 -0.011568 -3.122955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1503 2238 -0.020836 -1.032650 1.579220 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1535 2238 -0.014972 -0.994486 1.547140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1503 2240 0.020343 -0.996215 -1.562240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1548 2241 1.006060 0.003447 -3.109430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1549 2242 -1.004340 0.028839 3.128225 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2233 2242 1.985180 1.047830 -1.601940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1546 2242 0.032804 -0.018494 0.012422 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2257 2262 -0.993769 -0.018196 3.134645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2255 2263 -0.031108 -0.002930 -1.594510 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2248 2264 -1.000100 -0.955228 -1.588760 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2269 2277 0.019649 -0.007483 0.003144 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2272 2278 -0.011904 -0.026386 -3.129945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2239 2294 0.019513 -0.991739 1.547855 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1544 2294 -1.005630 0.962090 -1.568520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1527 2296 0.970664 -0.013707 -0.001891 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2292 2300 -1.003850 -1.003860 -1.562105 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2285 2300 -0.973684 0.024589 -0.010062 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2285 2301 -0.022549 0.015346 0.005144 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2288 2301 0.987109 -0.023667 3.074260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2288 2302 -0.007702 0.006190 3.138530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2286 2302 -0.001593 -0.013773 -0.036735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2299 2306 -0.049568 1.031460 -1.590380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2283 2307 -0.024297 -0.005727 1.602790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1544 2310 -0.998762 0.965888 -1.597660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2296 2312 0.059217 -0.009303 0.013513 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2253 2318 0.967605 0.001211 0.007747 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2316 2321 0.997886 0.048669 -3.139385 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2292 2322 -1.024360 1.008290 -1.559655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2307 2324 0.007075 -1.006220 -1.568600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2313 2325 0.003355 -0.001986 -3.113670 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2310 2328 0.034545 -0.018214 3.139630 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2308 2330 -0.022677 0.016248 3.117990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2319 2335 -0.009006 0.007122 -0.021243 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2317 2341 0.007285 -0.035176 0.032193 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2262 2344 -0.017692 -0.019994 -3.133105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2277 2349 0.007411 -0.058181 -0.033303 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2272 2349 0.945937 -0.039742 3.111260 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2272 2360 0.023198 0.001580 -0.004577 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2269 2361 -0.011365 0.007823 3.115745 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2348 2362 -0.029691 -0.014325 -3.124870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2342 2366 1.010620 1.039450 -1.574860 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2264 2366 0.015381 0.009471 3.119815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2267 2370 -0.985855 -0.015940 -0.000078 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2345 2370 1.007100 0.034338 0.019829 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2258 2370 0.014666 -0.006927 -0.038655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2267 2372 0.037180 1.018180 1.578850 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2277 2374 1.035730 0.008995 0.021836 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2331 2377 1.998730 -0.023033 -3.121160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2253 2382 1.007920 0.004715 -0.011004 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2319 2383 -0.011465 -0.013864 -0.013416 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2368 2384 0.035131 -0.032908 -0.032916 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2262 2385 -0.994153 -0.006190 -3.140365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2276 2388 0.008173 -0.007236 0.008200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2350 2388 -1.987120 -0.021922 0.002274 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2372 2388 0.020272 0.020533 0.013057 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2271 2392 -0.038646 -0.986068 -1.578280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2353 2392 -0.973547 0.017002 -0.014780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2354 2393 -0.981385 0.001947 -0.022202 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2270 2399 0.977351 0.029741 1.597045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2373 2401 -0.019967 0.020324 3.136865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2348 2401 0.974662 -0.061033 -3.141300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2274 2401 -0.970137 -0.014660 -0.019987 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2362 2402 -0.028185 0.020642 0.017967 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2347 2403 -0.021427 0.053936 -1.556190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2346 2403 1.026270 -0.030791 -1.590860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2259 2404 -1.030870 -0.021878 3.137975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2258 2404 -0.038098 0.061333 3.126965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2264 2406 -0.003616 0.017462 3.084005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2247 2407 -0.034864 -0.030890 -3.104370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2246 2408 -0.059554 0.031885 -3.121950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2245 2409 -0.006982 0.029146 3.140785 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2246 2409 -0.992440 -0.028750 3.140065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1548 2412 0.004777 0.006783 -0.017508 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1537 2412 1.008250 -0.021024 3.136290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2242 2412 0.010623 0.008900 -3.093865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2328 2413 -0.945884 -2.011440 1.557330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1542 2413 -1.027850 -0.000290 -0.012811 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1537 2414 -0.982370 -0.046381 3.130300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1502 2415 0.985726 0.021640 1.565360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2311 2415 0.008478 0.037638 -1.558565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2327 2415 -0.005447 0.037649 -1.581405 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2312 2416 0.020205 0.026861 -0.010060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2294 2416 0.013503 -0.020792 3.134610 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2308 2418 0.017066 0.003126 -3.119955 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2249 2420 1.008860 0.027893 3.118775 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2333 2420 -1.025130 0.005412 0.039601 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2322 2421 -0.989078 -0.012109 -3.133440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2244 2425 1.005390 0.005812 3.094215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2410 2426 -0.027883 0.015478 -0.049452 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1539 2427 -0.010268 -0.012567 -1.570310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2234 2427 1.026870 0.032934 -3.103680 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2411 2427 0.012937 -0.031155 0.008121 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 1547 2427 -0.004009 -0.043558 -1.549560 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2425 2430 -0.998652 -0.000349 -3.120755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2342 2430 0.978792 -0.986586 1.554720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2336 2432 -0.010458 -0.021764 0.021964 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2249 2433 0.006886 -0.033196 0.023304 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2308 2434 -0.973665 0.986734 -1.578015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2283 2434 0.006233 0.969780 -1.563535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2379 2435 0.007437 -0.010446 -1.549225 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2376 2438 -0.005506 0.051156 3.121250 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2281 2441 0.022229 0.005175 -0.013821 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2290 2442 0.940809 1.026170 -1.587750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2291 2443 -0.003096 -0.019362 -1.581960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2306 2443 0.985249 -0.001649 -1.564660 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2280 2446 -0.005263 0.032251 3.113180 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2439 2447 -0.026211 -0.018977 -0.025318 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2359 2447 0.018295 0.018307 -3.137055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2352 2448 -1.039080 0.984967 1.544240 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2351 2449 1.996050 0.012225 -0.032005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2396 2457 -0.951855 -2.038320 1.553570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2396 2458 -0.975535 -0.972501 1.564050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2396 2459 -1.016160 0.005521 1.567420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2452 2462 2.987290 -0.996176 1.574400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2456 2462 -0.000904 0.006725 -3.139375 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2455 2464 1.030430 0.010110 0.024949 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2456 2464 -0.988902 1.025800 1.558920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2455 2465 1.968482 0.008408 -0.007221 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2466 2471 0.972918 -3.985940 -1.562470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2468 2472 1.991260 0.005399 3.137940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2469 2474 -1.055920 -0.011992 3.120850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2470 2474 -1.941870 0.000239 3.081510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2465 2475 2.002280 -0.006063 1.578010 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2467 2475 0.011592 0.006777 1.585515 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2468 2476 -1.005610 1.022500 1.579270 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2467 2476 0.982608 -0.007486 0.001654 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2479 2488 -0.022910 0.983625 1.541030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2484 2492 -0.014958 -0.045523 0.007488 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2489 2493 -0.005237 0.056786 -3.110690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2485 2494 0.973658 -0.039629 0.006049 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2487 2495 0.001047 -0.007909 -0.007589 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2479 2495 -0.035051 -0.008055 -1.579040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2487 2497 -0.027184 2.013390 1.556460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2500 2504 3.009090 -0.965979 -1.588110 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2516 2520 3.000580 -1.012790 -1.546780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2520 2524 2.978920 -1.034160 -1.554130 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2521 2525 1.999010 -2.007880 -1.537180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2529 2533 -0.039996 0.010843 -3.128525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2530 2534 -2.007140 -0.009642 3.086590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2526 2534 1.012790 0.979168 -1.562665 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2531 2535 -3.986020 0.007247 -3.121785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2526 2535 1.001100 0.012974 -1.529460 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2504 2539 3.003588 0.011036 3.134610 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2506 2539 1.035750 0.017372 3.138295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2506 2540 1.001980 1.018410 1.569170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2510 2541 -0.995278 -0.018138 -0.000163 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2510 2543 0.988730 -0.029204 0.022761 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2511 2544 -0.015186 -0.974871 -1.613780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2512 2545 0.993470 0.038661 0.008698 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2516 2547 -1.002859 0.017899 0.008096 134.164079 0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 2515 2547 0.000394 -0.015932 0.006229 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2518 2547 -3.002030 -0.010979 0.025896 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2515 2548 0.008380 0.975292 1.561530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2514 2549 1.039730 1.988770 1.559360 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2515 2550 0.016093 2.970360 1.586440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2516 2551 -1.011130 4.051510 1.584460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2512 2556 -1.017470 2.998060 -1.562740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2543 2556 3.017890 -0.020124 -3.101180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2551 2556 -1.012550 3.976070 3.138085 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2543 2557 2.004630 0.006942 -3.107730 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2512 2558 -1.021740 0.985076 -1.595650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2543 2558 1.018410 -0.026155 -3.138920 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2511 2559 0.010839 0.048574 -3.116480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2543 2559 0.045857 0.027237 -3.135640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2560 2564 2.968080 -0.990440 -1.578495 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2562 2566 0.993102 -3.002250 -1.582185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2568 2572 2.991823 -0.985963 -1.571012 134.164079 -0.000000 0.000000 134.164079 0.000000 313.049517 +EDGE_SE2 2585 2590 -0.977317 -0.014275 -3.117732 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2583 2590 -1.003600 -0.021668 0.008088 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2583 2591 -0.029731 -0.005500 -0.019297 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2582 2593 -1.025910 0.015274 -3.141315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2588 2595 -0.988076 0.000827 -3.127625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2579 2596 0.982613 -0.008008 -0.031614 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2586 2597 0.991298 1.987910 1.570840 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2600 2606 0.018908 0.017495 -3.117600 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2598 2606 0.993412 1.006380 -1.545930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2598 2607 0.996163 0.014400 -1.601400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 19 2609 1.985500 0.020477 -3.130455 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 28 2612 -0.955087 -0.975877 -1.560180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 19 2612 0.002627 0.971752 1.532140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 29 2612 -2.001310 -1.013120 -1.557230 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2612 2616 2.983670 1.001490 1.549240 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 34 2616 0.985608 -2.984890 1.588370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 35 2618 -0.001673 -1.017620 1.584880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 36 2619 -1.064800 -0.024841 -0.014064 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 38 2619 -3.005700 0.012878 -0.011734 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 37 2620 -2.001733 1.023115 1.570485 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 34 2620 -0.011170 0.015413 -3.133093 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 54 2625 -0.964070 0.002367 -3.111275 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 51 2626 -0.016045 -1.036370 1.611140 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 52 2626 0.006116 -0.010217 3.121820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 52 2627 -1.029400 0.047217 3.122960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 66 2627 1.025560 0.037857 1.568860 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 50 2628 0.012420 -0.028549 -3.098320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 65 2630 -1.035540 -0.010688 -3.136920 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 0 2631 -1.023620 0.055117 -1.573860 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 63 2631 -0.005630 -0.024850 1.567155 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 22 2638 1.006150 -1.019240 1.544370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 23 2639 -0.036951 -0.005825 1.545170 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2641 2645 0.015156 -0.014290 -3.136035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2652 2665 0.977377 -0.028795 -3.130520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2642 2668 -0.010844 -0.019415 3.113900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2643 2668 -0.981452 0.006692 -3.137675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2639 2672 0.970295 0.004720 0.003516 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2602 2674 1.024000 -1.023260 1.565740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2602 2675 0.998882 0.037707 1.574410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2604 2675 -1.024860 0.004259 -1.571570 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2603 2676 0.004919 -1.035390 -1.598985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2673 2677 0.015662 0.001403 3.131950 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2642 2681 -1.014570 0.000117 -0.001738 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2648 2681 1.019310 -0.002031 0.009020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2684 2689 1.014710 -0.003670 -3.132280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2653 2689 -0.024594 0.023903 3.120305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2683 2690 -0.007961 -0.991156 1.547040 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2666 2691 0.998141 0.025122 0.008265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2685 2692 -0.984455 0.006881 -0.007268 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2688 2694 -0.035816 -0.006383 -3.118025 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2685 2694 1.000280 0.027036 0.013010 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2687 2694 -1.013140 0.032766 -0.007484 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2661 2695 1.996640 -0.013585 1.622020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2653 2701 0.036189 -0.007503 0.016669 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2653 2702 1.033080 0.014830 0.009241 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2655 2703 -0.042886 -0.015423 0.018364 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2656 2704 0.020698 0.028289 0.004777 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2660 2705 1.032410 -0.020183 -3.121410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2661 2706 -0.998126 0.015574 3.132045 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2658 2706 -0.008115 0.049036 -0.031003 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2660 2707 -1.025680 -0.003443 3.114583 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 151 2710 1.000440 0.038068 3.134940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 159 2710 0.024018 1.052870 -1.564045 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 160 2710 -0.938596 -1.012570 1.570490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 158 2711 1.023730 0.000867 -1.527455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 151 2711 -0.024405 -0.011444 3.133270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 150 2711 0.990101 -0.007391 -3.135675 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 158 2712 -0.005726 0.019596 -3.128745 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 160 2712 -0.005374 0.024230 -0.023646 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 158 2713 -1.025920 0.013928 3.121650 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 154 2714 -0.017657 0.009680 -0.002838 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 162 2714 0.010498 -0.029195 0.026940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 163 2715 -0.005393 0.023272 0.042140 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 155 2715 -0.010767 -0.008778 -0.016191 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 47 2718 1.004480 -0.005500 -3.136485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 47 2721 2.003970 -0.041706 -0.002433 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 163 2722 1.000360 -0.012054 3.138345 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2716 2722 0.001778 0.002305 3.127550 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2717 2722 -0.993591 0.017435 3.139845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2718 2724 -1.979610 0.050766 -0.016111 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2717 2725 -0.030326 0.006037 -0.012827 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2720 2726 0.008922 -0.017198 -3.125565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 72 2726 -1.004900 0.983664 -1.564830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 71 2726 1.051330 -0.040903 -3.132745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 60 2730 0.026860 0.025300 3.138285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 61 2737 0.001779 -0.015699 3.106455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 72 2743 -0.994278 0.018359 0.008797 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 71 2744 -0.007907 1.008150 1.529920 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2730 2746 0.005192 0.001416 0.005383 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2634 2747 0.985043 -0.004575 -0.018646 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2635 2747 -0.031844 0.007623 0.031544 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2635 2748 0.012230 -0.989152 -1.604160 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2688 2751 -1.042030 0.016455 -1.561520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2739 2755 0.007495 -0.007468 1.544740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2731 2755 0.008286 -0.003978 1.612600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 12 2756 -1.979840 -0.012390 3.118435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2636 2757 -0.982653 -2.047880 -1.531900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2750 2757 -0.976303 -0.002137 -0.002272 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2695 2759 0.022554 -0.011292 1.594455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 11 2762 1.028020 0.025775 3.123440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 4 2763 -1.013940 0.014668 0.009327 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2755 2763 0.053661 0.011556 -0.020207 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2637 2765 0.016991 0.009387 0.028735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2764 2769 1.000680 0.003185 -3.137285 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 2771 -0.023625 0.020536 -3.127125 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2765 2774 0.996924 0.025603 -0.007752 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2638 2774 -0.017385 0.033209 0.024027 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2769 2774 -1.005960 -0.008297 -3.102850 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2649 2777 -0.003220 0.022014 -0.006619 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2645 2778 -0.994625 0.004813 -3.114930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2653 2780 -0.950820 0.003170 -0.010588 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2665 2782 -0.972502 -0.034088 3.121310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2688 2782 0.008418 0.009993 -3.112785 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2702 2782 0.022374 -0.001457 -0.022731 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2694 2782 0.007018 0.019373 -0.017677 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2759 2782 -0.016564 1.008890 -1.567885 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2687 2784 -0.006609 -0.973832 -1.613810 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2752 2784 0.021073 0.017642 0.008884 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 12 2787 -1.029160 0.009293 0.041319 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 2787 -0.033435 -0.015255 1.519760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 2788 0.999565 0.005766 0.015786 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2765 2789 0.033230 -0.004835 -0.025489 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2773 2790 1.028670 0.010425 0.019674 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 24 2791 -0.998019 -0.028209 -1.590710 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2640 2791 -0.975382 0.020548 1.568580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2766 2792 -0.005532 0.027139 3.137760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2768 2792 0.007618 0.053857 -0.016193 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2638 2793 -1.010960 -0.002319 -3.076875 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2772 2794 0.015166 -0.007661 3.125990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 6 2798 0.020489 -0.034535 0.014470 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 15 2800 -0.024931 -0.974073 -1.568800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 30 2801 -0.991598 -0.020991 3.127365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 17 2801 -0.002192 -0.003856 -0.028796 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2612 2802 -0.984440 0.952441 -1.523900 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2611 2803 -0.014764 -0.004957 3.137705 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2615 2804 -4.016970 0.992687 1.555720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 17 2805 -0.019245 0.032116 -3.123755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2798 2808 -0.014094 0.020384 -3.130450 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 14 2808 -0.031563 0.015498 3.126575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 4 2811 -0.980723 0.036967 3.117465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3 2811 -0.016954 -0.017683 -1.545290 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2636 2811 -1.022940 0.002168 -1.561020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2728 2813 1.035700 -0.012188 3.137300 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2736 2813 1.023240 0.012659 -3.105945 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 0 2815 -0.997051 0.025189 -3.110175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2631 2815 0.039468 0.029969 -1.583165 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 48 2816 0.032458 0.024609 -0.048162 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2628 2818 0.004813 0.002606 3.128363 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 43 2818 0.983167 0.015971 -3.118305 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2626 2819 0.994178 0.017362 -1.541950 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 43 2820 -0.008621 -1.053610 -1.559005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 41 2820 2.005000 -1.015590 -1.594815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 43 2821 0.003047 -2.010120 -1.563475 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 67 2822 -0.012804 2.976370 1.559430 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2818 2822 0.971832 3.034160 1.540480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2821 2825 2.017730 -1.970210 -1.574670 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2822 2826 0.968501 -2.990720 -1.570570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2823 2827 -0.023077 -4.028450 -1.565210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2825 2829 1.997700 2.002120 1.592460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2830 2834 1.044180 3.015800 1.570435 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2831 2835 -0.001309 3.999202 1.586933 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2832 2836 2.996463 -0.992767 -1.577248 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2833 2837 1.999938 -1.983000 -1.568310 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2837 2841 1.981910 2.032150 1.530175 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 99 2848 3.048030 -0.022301 3.107565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 114 2848 1.000860 -3.023930 1.578630 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2845 2849 1.990910 2.035330 1.579310 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 106 2851 0.983462 0.009762 -3.135410 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 107 2851 0.009497 -0.002513 -3.128000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 108 2852 -0.001669 -0.010660 -0.006018 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2847 2852 -1.008280 3.978440 -3.122595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 77 2859 -1.985890 -0.034384 1.562210 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 75 2860 1.049770 0.003571 -0.006246 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2856 2862 0.026496 -0.009913 -3.126905 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 112 2863 -0.985411 0.001288 -1.544655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2861 2865 0.010684 -0.010867 -3.124140 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2858 2866 -0.014129 0.015423 0.024280 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2858 2867 0.997951 -0.028687 0.001281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2859 2867 0.006440 0.008744 -0.010248 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2859 2868 -0.018174 -0.960596 -1.560730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 76 2868 -0.019123 -0.004137 -0.017664 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2858 2868 0.951775 -0.959815 -1.609880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 76 2869 0.977922 -0.008595 0.003003 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 94 2871 1.036630 -0.026187 3.093215 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 96 2871 -0.988599 0.010926 1.544655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 100 2875 -1.022290 -0.004121 3.127620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2850 2875 0.976647 0.007622 3.132590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 124 2875 -1.029640 0.014627 -1.524355 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 86 2877 -1.020690 -0.023583 -0.020353 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 127 2878 -1.029470 0.018112 -0.001401 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 232 2879 -0.987914 0.051397 -0.008756 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 191 2880 -0.004494 0.959396 1.604400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 196 2882 -0.996133 1.018940 -1.546235 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 194 2882 0.012853 -0.033866 -0.009139 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 193 2882 0.965776 0.007158 0.000105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 195 2883 0.018329 -0.021106 -0.023299 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 225 2884 1.046110 -0.014796 -3.108460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 220 2885 1.015620 0.019858 -0.014608 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 222 2885 -1.007960 0.039564 -0.022075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 216 2886 -0.002182 0.020490 -3.133490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 215 2887 -0.017937 -0.011827 -1.565460 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 221 2887 2.008520 0.029331 -0.024883 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 213 2889 -0.015981 0.006586 3.135770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 202 2889 -0.998542 0.004665 0.005836 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 202 2890 -0.015374 -0.015257 -0.013667 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 203 2891 -0.018732 -0.014097 0.014955 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 208 2894 -0.020680 -0.040739 3.119605 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2897 2901 0.037486 -0.048527 3.114765 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2895 2902 -0.007534 -1.024890 1.588350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 327 2907 -0.028773 -3.973670 -0.029237 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2900 2908 -0.000355 -0.034415 -0.025161 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2905 2909 -0.021088 -0.020521 -3.112190 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2902 2911 0.991959 -0.003331 -0.028907 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 205 2913 -0.003229 0.044966 3.120620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 209 2913 -0.009344 0.005251 0.003524 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 210 2914 -0.001018 -0.006911 -0.004278 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 206 2918 -0.005201 0.007980 -0.018880 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2902 2919 1.025320 -0.052034 -1.560080 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2902 2920 0.015617 0.028334 3.125500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2911 2920 -0.979327 0.013309 -3.121115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2897 2921 -0.012342 -0.041760 0.028227 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2908 2922 0.007399 -0.010688 3.140772 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2897 2922 1.025950 -0.023184 -0.004247 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2900 2922 0.033673 0.009457 -3.132128 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2899 2924 0.035850 -1.022695 -1.563872 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 203 2930 1.032060 0.006277 3.107535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 212 2931 -0.997630 -0.003064 -0.035273 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2892 2931 -1.021700 0.050204 1.571490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 211 2931 0.029068 0.008406 -1.560020 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2929 2933 0.040753 -0.039378 -3.101455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2929 2937 0.024617 -0.037270 -0.010927 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2933 2937 0.004048 0.008653 -3.137360 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2928 2938 2.015830 -0.029276 0.006519 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2933 2938 -0.999881 -0.025362 3.113115 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2930 2940 0.047561 -0.007023 -3.099745 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2936 2942 -0.013130 0.019250 3.130960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2934 2942 -0.026766 0.025339 0.029965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2926 2943 0.986387 0.002755 1.562650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2927 2943 0.007629 -0.007321 1.586330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2935 2944 -0.002043 -1.025690 -1.587870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2942 2946 1.015600 -3.012090 -1.575490 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2927 2946 3.005270 0.034072 0.011916 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2951 2958 -0.003929 0.960500 -1.555180 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2950 2958 0.979305 1.022770 -1.544170 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2949 2959 1.983420 -0.002985 -1.593110 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2952 2960 0.002539 -0.029643 0.017295 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2951 2960 0.004653 0.996667 1.579315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2953 2961 0.012524 0.000884 -0.008737 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2954 2962 0.011271 0.001231 -0.028917 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2955 2963 0.008787 -0.033430 -0.029568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2955 2964 -0.004873 -1.030220 -1.538385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2968 2972 1.997310 -0.011277 3.085525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2969 2973 -0.012960 -0.022137 -3.116330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2968 2974 0.025458 -0.019177 3.116685 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2970 2974 -2.009320 -0.027604 3.096805 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2967 2975 -0.015049 -0.020031 1.579575 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2977 2981 0.025804 -0.000320 3.130815 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2967 2983 -0.031991 0.004434 -3.109190 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2966 2983 1.002040 0.008790 -3.122650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2965 2983 1.991640 0.021597 -3.134250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2975 2984 -0.020864 -1.008890 -1.548425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2977 2984 -0.945491 -0.018789 -0.021030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2978 2986 0.013580 0.005269 -0.019051 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3002 3010 1.018070 -1.025680 1.589515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3005 3013 -0.027617 0.046750 -0.006725 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3008 3014 -0.011092 0.007399 -3.110755 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3007 3015 -0.012668 0.006546 -0.049300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3015 3032 1.001980 -0.010183 0.014568 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3025 3033 0.023798 0.004753 0.010325 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3026 3035 0.938790 0.010191 0.031292 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3040 3047 -0.988460 0.033880 -3.110480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3036 3050 -0.000018 -0.007460 -3.108260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3018 3060 -0.022324 -0.021271 3.137040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3016 3061 0.983050 0.020778 -3.123205 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3032 3062 -0.970129 -0.987825 1.617420 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3031 3063 0.029287 -0.011266 -1.610075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3006 3064 0.010322 0.006418 3.122465 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3005 3065 -0.028855 0.009832 3.138565 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3010 3066 0.001369 -0.003149 0.004075 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3023 3095 0.017423 0.004221 3.129985 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3092 3097 0.977131 0.008164 -3.136625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3093 3097 -0.028782 -0.006193 -3.139035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3091 3106 0.987192 0.025244 -3.131620 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3090 3107 0.990834 -0.009693 3.132595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3044 3114 0.025139 -0.006542 3.113778 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3044 3115 -1.007030 -0.031591 -3.130005 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3117 3123 1.986340 3.988200 1.574320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3122 3126 0.969149 -3.002360 -1.599930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3130 3134 0.978883 -3.026130 -1.587260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3127 3142 0.013162 -0.991279 1.548480 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3128 3143 -1.013270 -0.027119 1.571480 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3127 3143 -0.011349 0.000407 1.561580 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3125 3143 1.989940 -0.029407 1.562530 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3124 3143 2.996740 0.026599 1.554400 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3140 3146 -0.049366 -0.001484 3.139845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3141 3146 -1.024050 0.001738 -3.111800 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3138 3148 1.015440 1.001230 1.542615 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3055 3152 -0.990230 0.007642 3.133370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3053 3152 1.013920 0.000788 -3.137795 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3052 3153 0.963892 -0.009629 3.126070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3050 3154 1.951050 -0.031665 -3.101935 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3120 3159 -1.029803 -0.009906 -0.028531 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3119 3159 0.015164 -0.021727 1.597990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3122 3160 -3.006710 0.996972 1.583957 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3120 3160 -0.972106 1.031470 1.579500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3118 3160 -0.010999 -0.016407 -3.125915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3117 3161 0.030089 -0.039532 -3.137045 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3116 3161 1.017680 0.025563 -3.133625 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3116 3162 0.018731 0.005646 -3.100385 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3114 3162 1.002550 -1.015140 1.545070 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3116 3163 -0.987805 -0.010547 -3.132938 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3042 3163 0.993314 0.014586 1.570640 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3114 3164 0.034235 -0.007980 3.125225 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3041 3164 1.004670 0.006800 3.140335 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3041 3166 -0.986861 0.004214 3.098185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3048 3168 -0.013818 -0.012328 0.015957 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3051 3171 -0.007414 -0.023891 -0.038865 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3048 3173 1.003590 -0.005407 3.128930 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3047 3174 -0.024316 1.002040 -1.573105 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3167 3174 0.038953 0.998947 -1.575145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3048 3175 -1.050800 0.016191 -3.126515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3171 3178 -1.007370 0.017753 0.031612 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3037 3181 0.022479 0.010981 -0.009902 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3177 3181 -0.010849 0.053531 3.127890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3169 3181 -0.000961 -0.039884 3.126140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3047 3182 -0.052512 1.010490 -1.592445 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3174 3182 -0.022968 -0.008221 -0.009749 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3173 3185 -0.018943 0.006783 3.098635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3050 3186 -0.001257 -0.017975 -0.007328 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3035 3186 0.017816 1.008570 -1.567330 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3157 3187 -2.009850 -0.010512 -1.553250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3050 3187 1.015650 0.010763 -0.045949 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3155 3187 0.032368 -0.012964 -3.102760 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3028 3188 -0.038930 0.019512 0.006144 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3178 3189 0.995008 -2.010420 -1.551150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3007 3191 -0.021118 -0.001473 3.141425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3096 3192 -0.004636 -0.014010 0.006354 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3098 3194 -0.004196 0.000375 -0.015991 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3106 3196 0.003169 -0.024971 3.109700 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3101 3197 -0.031735 0.023065 0.021497 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3038 3198 1.020660 0.992148 -1.583240 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3103 3198 -1.008600 -0.016656 0.023963 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3102 3199 1.004770 -0.011218 0.020271 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3038 3200 0.983218 0.995358 1.555485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3110 3200 -0.027919 0.018069 3.136735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3167 3200 0.963062 0.006110 -0.008370 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3183 3200 0.011140 0.972561 1.530975 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3175 3200 -0.028225 0.999141 1.582415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3110 3202 -1.983320 0.058264 -3.110330 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3196 3203 -1.035560 -0.017198 3.133145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3097 3205 -0.020896 0.005524 3.111785 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3093 3206 1.000560 0.015970 0.005689 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3063 3207 0.007170 0.029412 -3.111980 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3029 3209 -0.009251 0.009925 3.140585 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3172 3210 -1.022710 1.019190 -1.527740 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3034 3210 -0.014326 -0.035931 -0.019600 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3179 3211 -0.003624 0.017208 1.588520 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3187 3212 0.995337 0.010824 0.026911 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3052 3212 0.017350 -0.024213 0.033434 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3055 3214 -1.004390 0.011944 0.015916 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3151 3215 0.022296 0.026646 1.554780 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3152 3215 -0.990852 -0.000816 3.101015 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3055 3216 -0.001585 0.994104 1.535520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3150 3217 -1.025740 -0.009229 3.124960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3139 3219 0.023256 -0.010427 -1.587690 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3137 3221 -0.008971 -0.003792 3.140820 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3136 3223 -1.006180 0.000036 3.131825 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3136 3224 0.065080 -0.006809 0.028181 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3137 3224 -1.015730 0.013580 -0.013720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3137 3225 -0.000822 -0.022151 0.010455 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3138 3227 0.992078 -0.019653 0.014712 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3220 3227 -1.005880 0.038713 -3.136415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3140 3227 -0.994390 -0.011129 1.580590 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3149 3229 -0.019940 -0.017109 -0.017098 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3216 3230 -0.009552 -0.014342 -3.126730 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3214 3231 1.005710 -0.027593 -1.629250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3152 3232 0.031452 -0.026554 0.023032 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3054 3232 0.005306 0.002510 -3.112425 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3053 3232 0.997945 -0.001094 -3.126925 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3154 3233 -0.975543 0.012951 -0.026868 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3190 3237 -0.966039 0.006221 -0.028904 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3023 3239 -0.010565 -0.039264 1.567515 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3062 3239 1.015790 0.021934 1.598195 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3063 3239 -0.032374 0.021041 1.570595 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3207 3239 0.032676 -0.002245 -1.542900 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3017 3241 0.012777 0.004542 0.050449 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3059 3243 0.020475 0.005166 1.572490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2994 3243 1.013420 -0.037151 -3.117950 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2994 3244 1.033330 0.991423 1.571065 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2998 3245 -1.003968 0.003192 0.014345 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 2997 3246 0.986778 0.004026 0.003667 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3000 3248 0.009733 -0.006027 -0.029832 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3001 3248 -0.972750 0.030673 -0.013552 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3002 3249 -0.966120 -0.019777 0.002915 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3011 3251 -0.013521 -0.015243 -1.576808 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3010 3251 0.967277 0.000558 -1.561425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3081 3253 -0.018064 0.049643 3.128635 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3081 3254 -0.978560 0.041142 3.113415 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3080 3254 -0.053913 0.031810 -3.130370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3079 3255 0.039905 0.006101 -1.572240 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3078 3255 1.001045 0.009543 -1.567678 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3080 3255 -0.985000 0.018498 3.106645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2997 3263 1.992830 0.030991 -3.115545 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3260 3265 0.975766 0.017836 -3.103500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3261 3265 0.006395 -0.012064 3.136145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3259 3266 0.027183 0.998334 -1.571490 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3258 3266 0.981972 0.960656 -1.560380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3261 3267 -2.004950 0.006142 -3.116520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3259 3268 1.018110 -0.007162 0.029476 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3260 3268 -1.009220 -1.014120 -1.557570 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3260 3269 -0.982024 -1.994270 -1.576150 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3266 3270 0.998586 2.985210 1.589000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3259 3270 3.020730 -0.006657 -0.029223 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2987 3273 -0.014544 2.005040 -1.594330 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2988 3277 0.996535 0.006323 0.025041 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2989 3277 -0.006471 -0.002537 -0.021440 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2990 3280 0.014523 -0.003085 -3.140087 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3277 3281 -0.023799 -0.013400 3.131935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3276 3283 -0.957795 -0.008174 3.127685 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3273 3283 2.017770 0.017267 3.116635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2987 3284 0.962216 -0.012651 0.034364 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3274 3284 1.012750 1.002840 1.562770 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3273 3284 1.993440 1.046530 1.563040 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2979 3284 0.982560 0.015196 -0.025709 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3263 3287 -0.029520 0.046339 1.539060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 2998 3287 0.961422 -0.021989 -1.547265 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3262 3288 0.988331 0.980778 1.558050 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3249 3288 -0.963944 -0.018753 0.000638 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3012 3289 -0.996686 -2.024750 1.575200 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3248 3289 0.987118 0.056675 0.000520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3000 3289 1.020160 0.027430 -0.013865 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3067 3290 -0.007801 1.023480 -1.581965 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3003 3291 -0.023773 -0.025123 0.026453 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3083 3291 -0.000526 0.049317 1.610300 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3004 3292 0.038275 0.027318 0.031098 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3010 3292 0.016038 -0.008845 3.122000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3032 3294 -2.003470 -0.019289 0.014210 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3191 3295 0.047578 0.008740 -3.108815 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3205 3297 0.002818 0.007242 -3.110055 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3092 3300 -0.012357 -0.018684 0.006590 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3297 3301 -0.008960 0.000573 -3.114940 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3014 3303 1.020680 0.024237 -1.541260 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3030 3303 1.028920 0.002771 1.588990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3006 3304 -0.009727 -0.028630 3.108775 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3238 3305 3.020690 -0.009136 -0.009343 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3006 3305 -0.976324 -0.047975 -3.121990 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3292 3306 0.002791 0.010694 3.096645 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3084 3308 0.013598 -0.018127 -0.011803 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3069 3309 -0.008321 -0.001467 0.015668 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3071 3311 0.019599 -0.004642 0.002660 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3076 3316 -0.994708 1.011810 1.580000 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3074 3317 -1.005920 -0.002685 3.105510 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3087 3319 -0.007770 0.035686 -1.611100 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3311 3320 0.027145 1.000458 1.589978 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3073 3321 -0.018838 0.003350 -0.020423 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3317 3321 0.010735 0.000628 -3.128750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3313 3321 -0.010312 -0.003634 0.001370 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3312 3321 1.016800 0.018472 0.010258 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3074 3322 -0.040914 0.011727 -0.021025 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3075 3323 0.007302 -0.006454 0.066896 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3076 3323 -1.020910 0.016340 -1.588380 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3325 3329 0.000408 -0.026002 3.134482 89.442719 -0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3075 3330 0.965454 0.003569 -3.140585 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3315 3330 0.978579 0.024351 3.133910 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3325 3330 -0.990014 0.027186 -3.115365 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3323 3331 0.032932 0.022665 -3.137595 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3324 3332 0.001837 0.005469 0.003477 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3323 3332 0.979045 0.016864 0.027197 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3329 3333 0.018889 0.005700 -3.123880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3328 3334 -0.022111 0.026929 3.098655 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3326 3334 0.006067 0.052464 0.008281 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3327 3335 0.040524 0.010327 -0.012127 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3327 3339 -0.028995 3.988970 1.609960 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3271 3355 0.011072 -4.006300 1.565060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3350 3355 1.005680 4.021690 1.550270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3354 3358 1.016220 -3.039670 -1.593930 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3356 3360 3.007000 -1.035120 -1.581870 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3353 3361 0.003598 -3.991810 3.108635 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3351 3364 3.008030 -0.006582 3.125270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3363 3367 0.038822 -3.989280 -1.599975 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3352 3367 -1.027100 -0.006491 1.585650 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3353 3367 -1.991122 0.023337 1.565678 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3365 3369 2.010080 2.024810 1.586755 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3369 3373 0.003175 0.029224 3.138880 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3368 3374 0.013354 -0.004092 3.102520 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3369 3375 -2.018380 0.024854 3.121490 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3365 3375 1.977720 0.006191 -1.608880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3355 3376 -3.951720 0.975272 1.562880 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3350 3377 -0.996170 -0.033531 -3.131365 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3349 3377 0.004836 0.013466 3.132720 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3345 3378 2.001810 0.975390 -1.561275 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3346 3378 1.039450 1.011150 -1.575165 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3347 3379 -0.011195 -0.010712 -1.577565 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3348 3379 -1.017020 -0.007679 -3.106095 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3348 3380 -1.018335 -1.013008 -1.572277 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3347 3380 1.024860 0.001338 0.010943 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3347 3381 2.008740 0.005463 -0.008760 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3378 3382 0.978103 3.012880 1.632975 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3371 3383 -0.025519 -4.014915 -0.018932 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3387 3391 0.031890 3.981140 1.546525 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3388 3392 3.022650 1.026030 1.591030 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3392 3396 2.023940 0.007535 3.105270 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3393 3397 0.001861 0.030085 -3.133845 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3392 3398 0.008989 -0.002512 3.138550 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3388 3399 2.982340 -0.013834 -1.563415 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3390 3399 1.011153 -0.005544 -1.568170 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3391 3399 0.026188 0.001226 -1.557035 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3391 3400 1.016930 0.032600 0.001887 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3414 3423 1.011640 -0.006550 1.575750 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3425 3430 -0.990564 0.006053 -3.134525 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3418 3434 0.033170 0.015964 0.002203 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3420 3434 -0.000364 -0.006055 -3.134320 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3414 3437 0.952499 -1.991030 1.557820 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3415 3438 -0.014616 -0.980767 1.611120 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3423 3438 -1.027110 -0.019608 0.003563 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3431 3438 -0.002667 0.955677 -1.572350 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3415 3439 -0.023824 0.006743 1.578500 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3429 3441 0.009141 0.024752 -3.133177 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3426 3442 -0.004190 0.032259 -0.004280 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3429 3442 -0.988224 -0.036270 3.133255 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3429 3445 0.030241 0.015364 -0.044216 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3425 3445 -0.014296 -0.008301 -3.107395 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3440 3446 0.020401 -0.009372 -3.121535 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3439 3454 1.000290 0.012275 -3.130790 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3448 3454 0.014237 0.019249 -3.134830 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3432 3455 -0.978312 0.032874 -0.012273 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3439 3455 0.023475 -0.002436 -3.122700 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3423 3456 1.006900 0.008129 -0.017185 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3448 3457 1.014220 0.019537 -0.035437 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3464 3470 -0.006609 0.018518 3.139403 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3463 3471 -0.008586 0.024989 1.572465 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3464 3471 -1.033940 -0.023548 -3.119735 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3462 3471 1.006910 -0.008297 1.605240 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3464 3472 0.021041 -0.005002 0.008941 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3443 3476 -1.024310 -0.018902 -3.123725 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3444 3476 0.013877 -0.002619 0.004935 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3442 3476 -0.012528 -0.053588 -3.125785 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3445 3477 -0.001225 0.016374 0.006063 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3431 3478 -1.022450 0.018633 0.035724 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3415 3479 0.036866 0.014549 -3.124125 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3416 3480 0.007039 -0.039743 0.014502 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3437 3481 -0.010448 0.001084 -3.140440 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3433 3481 0.004163 -0.020544 0.029400 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3420 3482 0.003153 0.032379 -3.118140 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3419 3483 0.064131 -0.020825 0.004060 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3435 3484 0.017613 -1.016570 -1.558315 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3436 3485 -1.032430 2.011510 1.553250 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3411 3487 3.993780 0.013439 -1.578425 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3409 3491 1.966110 0.010055 3.132140 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3412 3491 -0.999288 -0.006317 1.544615 89.442719 0.000000 0.000000 89.442719 0.000000 134.164079 +EDGE_SE2 3404 3496 -1.022640 -3.001550 1.555070 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3403 3497 2.001320 0.041642 -3.114135 44.721360 -0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3404 3498 -1.010340 -1.019740 1.521890 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3405 3498 -2.018110 -1.032670 1.622040 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3403 3499 -0.031191 0.017659 -3.112485 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 +EDGE_SE2 3402 3499 1.022250 0.034739 -3.114145 44.721360 0.000000 0.000000 44.721360 0.000000 44.721360 diff --git a/examples/data/parking-garage.g2o b/examples/data/parking-garage.g2o new file mode 100644 index 0000000..2d1ad6a --- /dev/null +++ b/examples/data/parking-garage.g2o @@ -0,0 +1,7936 @@ +VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 1 4.15448 -0.0665288 0.000389663 -0.0107791 0.00867285 -0.00190021 0.999902 +VERTEX_SE3:QUAT 2 8.31419 -0.173106 -0.0129024 -0.00802114 0.00792915 0.00172397 0.999935 +VERTEX_SE3:QUAT 3 12.6035 -0.1837 -0.0848858 -0.0103926 -0.00786875 0.0167457 0.999775 +VERTEX_SE3:QUAT 4 16.8016 -0.108137 -0.0601645 -0.00253999 0.00220233 0.0263555 0.999647 +VERTEX_SE3:QUAT 5 20.9607 0.0310604 -0.085476 -0.00864918 0.00189323 0.0207459 0.999746 +VERTEX_SE3:QUAT 6 25.492 0.0946081 -0.127169 -0.00444317 0.00936269 0.0151893 0.999831 +VERTEX_SE3:QUAT 7 29.583 0.104272 -0.194878 -0.00678458 0.0141998 0.012983 0.999792 +VERTEX_SE3:QUAT 8 34.0787 0.183728 -0.292361 -0.00473159 0.012228 0.0359905 0.999266 +VERTEX_SE3:QUAT 9 38.3977 0.671044 -0.378781 0.00383224 0.015159 0.122622 0.99233 +VERTEX_SE3:QUAT 10 42.3092 2.15489 -0.498543 0.00476216 0.0111507 0.256225 0.966541 +VERTEX_SE3:QUAT 11 45.7973 4.69776 -0.562561 0.00773828 0.0131353 0.38897 0.921124 +VERTEX_SE3:QUAT 12 48.3255 7.94648 -0.59199 0.00696949 0.0142966 0.499312 0.866276 +VERTEX_SE3:QUAT 13 50.2886 11.8218 -0.632211 0.0043765 0.0112782 0.54974 0.835248 +VERTEX_SE3:QUAT 14 51.8675 15.5579 -0.667529 0.000729013 0.00688092 0.570668 0.821151 +VERTEX_SE3:QUAT 15 53.1556 19.3964 -0.692883 -0.00569501 0.00803061 0.665472 0.746358 +VERTEX_SE3:QUAT 16 52.7629 23.7089 -0.695487 0.0152856 -0.00941798 0.826816 0.562186 +VERTEX_SE3:QUAT 17 50.7512 27.1768 -0.58678 0.0114423 -0.000551325 0.911879 0.410299 +VERTEX_SE3:QUAT 18 47.6926 30.0891 -0.522667 0.0109823 0.0107887 0.951396 0.307587 +VERTEX_SE3:QUAT 19 44.1188 32.5473 -0.4667 0.014009 0.0129989 0.962618 0.270187 +VERTEX_SE3:QUAT 20 40.5032 34.8185 -0.401651 0.0102884 0.0141354 0.966145 0.257407 +VERTEX_SE3:QUAT 21 36.5187 37.1607 -0.351521 0.0173424 0.0145557 0.968713 0.24715 +VERTEX_SE3:QUAT 22 32.9935 39.1494 -0.25859 0.0103804 0.0133977 0.971343 0.237075 +VERTEX_SE3:QUAT 23 29.2275 41.1294 -0.197772 0.00953295 0.0100552 0.975212 0.22084 +VERTEX_SE3:QUAT 24 25.0731 43.1332 -0.141528 0.00790445 0.0110768 0.978983 0.203488 +VERTEX_SE3:QUAT 25 21.0176 44.953 -0.0935092 0.00932127 0.0147984 0.982128 0.187399 +VERTEX_SE3:QUAT 26 16.6157 46.7425 -0.0417203 0.00851879 0.014545 0.984656 0.173693 +VERTEX_SE3:QUAT 27 12.0661 48.4451 -0.00604308 0.00638403 0.0137028 0.987019 0.159889 +VERTEX_SE3:QUAT 28 8.18542 49.7695 0.0198388 0.00612157 0.0135343 0.989454 0.144083 +VERTEX_SE3:QUAT 29 3.38409 51.1985 0.0664245 0.00250893 0.0102753 0.99204 0.125475 +VERTEX_SE3:QUAT 30 -1.40165 52.4516 0.08575 0.00172901 0.0104949 0.994094 0.107998 +VERTEX_SE3:QUAT 31 -6.02002 53.5102 0.115937 -0.0013129 0.00970546 0.995421 0.0950891 +VERTEX_SE3:QUAT 32 -10.8048 54.4903 0.119075 -0.00223305 0.00860771 0.996458 0.083615 +VERTEX_SE3:QUAT 33 -15.4279 55.3133 0.108045 -0.00462889 0.0101332 0.997553 0.0690242 +VERTEX_SE3:QUAT 34 -19.9421 55.9821 0.0799549 -0.0069323 0.00883312 0.998445 0.0546082 +VERTEX_SE3:QUAT 35 -24.4127 56.5277 0.0423674 -0.0102622 0.011144 0.999082 0.0400608 +VERTEX_SE3:QUAT 36 -28.6809 56.9149 -0.0267491 -0.0091308 0.0154043 0.999537 0.0245942 +VERTEX_SE3:QUAT 37 -32.9258 57.1556 -0.0699266 -0.0140077 0.0137335 0.999771 0.00859193 +VERTEX_SE3:QUAT 38 -37.6373 57.2362 -0.174829 0.0137233 -0.0130339 -0.999768 0.0102952 +VERTEX_SE3:QUAT 39 -41.8811 57.1655 -0.257988 0.0134501 -0.00823151 -0.999472 0.0284052 +VERTEX_SE3:QUAT 40 -46.3383 56.9468 -0.302992 0.0204619 -0.0159739 -0.998544 0.0472943 +VERTEX_SE3:QUAT 41 -50.4695 56.5769 -0.416389 0.0168569 -0.00841387 -0.99827 0.0556947 +VERTEX_SE3:QUAT 42 -54.5723 56.2303 -0.503581 0.0130324 -0.00959519 -0.999449 0.0289813 +VERTEX_SE3:QUAT 43 -58.697 56.6393 -0.615463 -0.0165263 0.00625994 0.990446 0.136763 +VERTEX_SE3:QUAT 44 -62.1924 58.589 -0.752286 0.0146379 -0.0224801 0.916802 0.398441 +VERTEX_SE3:QUAT 45 -64.4811 62.1685 -0.65459 -0.0279199 -0.00866771 0.85095 0.524433 +VERTEX_SE3:QUAT 46 -66.1343 66.0818 -0.803284 -0.0258185 -0.01178 0.825164 0.56418 +VERTEX_SE3:QUAT 47 -67.5001 70.2838 -0.917276 -0.0381335 -0.00936819 0.797617 0.601884 +VERTEX_SE3:QUAT 48 -68.296 74.2712 -1.09623 -0.0109762 -0.0143128 0.764646 0.644198 +VERTEX_SE3:QUAT 49 -68.7272 78.4764 -1.03921 0.0113477 -0.0309399 0.722979 0.690083 +VERTEX_SE3:QUAT 50 -68.5322 82.5585 -0.786977 -0.00440359 -0.0158666 0.667894 0.744074 +VERTEX_SE3:QUAT 51 -67.7019 86.7579 -0.744158 -0.0205182 0.00629109 0.609358 0.792605 +VERTEX_SE3:QUAT 52 -65.9614 90.8068 -0.885501 -0.026198 0.00648246 0.497865 0.866835 +VERTEX_SE3:QUAT 53 -63.4285 93.9861 -1.01015 -0.0210627 0.00420054 0.409642 0.911994 +VERTEX_SE3:QUAT 54 -60.4434 97.0429 -1.10769 -0.0196075 0.00390829 0.397571 0.917353 +VERTEX_SE3:QUAT 55 -57.4025 100.256 -1.20542 -0.0202644 0.00657573 0.411151 0.911318 +VERTEX_SE3:QUAT 56 -54.4827 103.553 -1.32324 -0.0237554 0.0107997 0.42489 0.904869 +VERTEX_SE3:QUAT 57 -51.5074 107.037 -1.48355 -0.0231383 0.00556226 0.430637 0.902211 +VERTEX_SE3:QUAT 58 -48.5159 110.604 -1.60957 -0.0233103 0.00701009 0.435326 0.899944 +VERTEX_SE3:QUAT 59 -45.5001 114.31 -1.74902 -0.0264172 0.0107518 0.4409 0.897103 +VERTEX_SE3:QUAT 60 -43.0202 117.443 -1.89113 -0.0275313 0.00912821 0.44735 0.893888 +VERTEX_SE3:QUAT 61 -40.1961 121.13 -2.0759 -0.027614 0.00993353 0.45433 0.89035 +VERTEX_SE3:QUAT 62 -37.4557 124.821 -2.23314 -0.0287122 0.00358654 0.456979 0.889006 +VERTEX_SE3:QUAT 63 -34.7926 128.408 -2.33965 -0.0322415 -0.00349108 0.453797 0.890515 +VERTEX_SE3:QUAT 64 -32.1758 131.863 -2.42104 -0.0318441 -0.00321769 0.4533 0.890783 +VERTEX_SE3:QUAT 65 -29.4443 135.492 -2.49634 -0.0301384 -0.00532763 0.457259 0.888807 +VERTEX_SE3:QUAT 66 -26.6444 139.299 -2.5616 -0.0286911 -0.00605697 0.463264 0.885735 +VERTEX_SE3:QUAT 67 -23.9487 143.05 -2.62279 -0.0272281 -0.00502947 0.468827 0.882856 +VERTEX_SE3:QUAT 68 -21.3376 146.82 -2.66819 -0.0289382 -0.0021809 0.47224 0.880992 +VERTEX_SE3:QUAT 69 -18.967 150.133 -2.72183 -0.0274464 -0.0030461 0.46395 0.885431 +VERTEX_SE3:QUAT 70 -16.496 153.632 -2.76175 -0.0254295 -0.00424499 0.476921 0.878568 +VERTEX_SE3:QUAT 71 -14.1679 157.394 -2.80447 -0.0286443 -0.00247772 0.521832 0.852563 +VERTEX_SE3:QUAT 72 -12.5067 161.428 -2.90257 -0.0271616 0.000268473 0.630113 0.776029 +VERTEX_SE3:QUAT 73 -12.3262 165.517 -3.04827 -0.0258699 0.00127879 0.774721 0.631772 +VERTEX_SE3:QUAT 74 -13.9103 169.495 -3.25136 -0.00422411 0.00365848 0.886175 0.463318 +VERTEX_SE3:QUAT 75 -16.7649 172.642 -3.24582 0.00336106 -0.00230208 0.946996 0.32122 +VERTEX_SE3:QUAT 76 -20.1102 174.949 -3.25494 -0.0250569 0.0079305 0.955028 0.295347 +VERTEX_SE3:QUAT 77 -23.1495 177.748 -3.42866 -0.0119619 -0.00475952 0.874964 0.484017 +VERTEX_SE3:QUAT 78 -24.1324 181.917 -3.47574 -0.00891812 -0.00713501 0.666444 0.745468 +VERTEX_SE3:QUAT 79 -22.5078 185.816 -3.47603 -0.00883906 -0.000232176 0.480294 0.877063 +VERTEX_SE3:QUAT 80 -19.9725 189.153 -3.52048 -0.0123589 0.00511947 0.44244 0.896698 +VERTEX_SE3:QUAT 81 -17.4747 192.276 -3.60298 -0.0120193 0.00396639 0.444151 0.895863 +VERTEX_SE3:QUAT 82 -14.9016 195.565 -3.66846 -0.0132396 0.00512804 0.452097 0.891856 +VERTEX_SE3:QUAT 83 -12.3912 198.93 -3.74116 -0.0156516 0.00472438 0.465972 0.884648 +VERTEX_SE3:QUAT 84 -10.071 202.321 -3.8032 -0.010869 0.000742341 0.505667 0.86266 +VERTEX_SE3:QUAT 85 -8.41644 206.35 -3.85198 -0.00627692 0.0016562 0.645389 0.763827 +VERTEX_SE3:QUAT 86 -8.45973 210.504 -3.88686 -0.00143735 0.00267593 0.79715 0.603773 +VERTEX_SE3:QUAT 87 -10.3896 214.291 -3.91336 0.00394626 0.00490025 0.911321 0.411649 +VERTEX_SE3:QUAT 88 -13.5319 217.022 -3.8801 -0.0108555 0.00471677 0.956871 0.290272 +VERTEX_SE3:QUAT 89 -16.8909 219.226 -3.98083 -0.0168841 0.00199999 0.961225 0.27524 +VERTEX_SE3:QUAT 90 -20.4208 221.659 -4.09885 -0.00790936 -0.00372158 0.952692 0.303812 +VERTEX_SE3:QUAT 91 -23.9123 224.396 -4.16463 -0.0100075 -0.00471122 0.945419 0.325669 +VERTEX_SE3:QUAT 92 -27.0288 226.99 -4.22063 -0.00726548 -0.0025421 0.944752 0.327694 +VERTEX_SE3:QUAT 93 -30.2705 229.652 -4.26338 -0.00608671 0.00314674 0.946696 0.322056 +VERTEX_SE3:QUAT 94 -33.5794 232.275 -4.30339 -0.00213429 0.00507433 0.949817 0.312759 +VERTEX_SE3:QUAT 95 -37.1049 234.912 -4.34462 -0.0170837 0.00809097 0.952534 0.303846 +VERTEX_SE3:QUAT 96 -40.6973 237.518 -4.49741 -0.0138288 0.00315334 0.954258 0.298646 +VERTEX_SE3:QUAT 97 -44.2724 240.093 -4.60382 -0.0121723 -0.000810103 0.954907 0.296655 +VERTEX_SE3:QUAT 98 -47.7257 242.573 -4.68974 -0.0128673 0.00199956 0.955569 0.29448 +VERTEX_SE3:QUAT 99 -51.2488 245.065 -4.79173 -0.0148089 0.0010673 0.956105 0.292648 +VERTEX_SE3:QUAT 100 -54.8727 247.632 -4.8901 -0.012357 0.00289244 0.956426 0.291698 +VERTEX_SE3:QUAT 101 -58.1529 249.927 -4.97533 -0.0034692 0.00611114 0.960487 0.278238 +VERTEX_SE3:QUAT 102 -61.7831 252.211 -5.01199 -0.00668511 0.0137645 0.972411 0.232773 +VERTEX_SE3:QUAT 103 -65.8392 253.87 -5.11772 -0.0160298 0.0174911 0.993654 0.109947 +VERTEX_SE3:QUAT 104 -69.9843 254.282 -5.24382 0.0109974 -0.0222989 -0.998703 0.0444403 +VERTEX_SE3:QUAT 105 -74.0811 253.334 -5.29096 0.0101445 -0.0193043 -0.97622 0.215685 +VERTEX_SE3:QUAT 106 -77.5121 251.091 -5.27009 0.00191451 -0.0145526 -0.921525 0.388042 +VERTEX_SE3:QUAT 107 -79.9138 247.678 -5.20017 -0.010501 -0.0150777 -0.80515 0.592787 +VERTEX_SE3:QUAT 108 -80.2268 243.488 -5.07164 -0.0115699 -0.0201824 -0.617303 0.786381 +VERTEX_SE3:QUAT 109 -78.4499 239.783 -4.90246 -0.0136509 -0.0158706 -0.427863 0.903601 +VERTEX_SE3:QUAT 110 -75.4115 236.793 -4.74221 -0.0126031 -0.00704097 -0.330569 0.943672 +VERTEX_SE3:QUAT 111 -71.9578 234.173 -4.66155 -0.0107702 -0.000374284 -0.294698 0.95553 +VERTEX_SE3:QUAT 112 -68.4241 231.728 -4.61583 -0.0166058 -0.000965339 -0.285736 0.958164 +VERTEX_SE3:QUAT 113 -64.605 229.135 -4.54928 -0.0168387 -0.00260308 -0.285706 0.958166 +VERTEX_SE3:QUAT 114 -61.258 226.84 -4.47897 -0.0190801 -0.00208575 -0.284813 0.958391 +VERTEX_SE3:QUAT 115 -57.8552 224.518 -4.40056 -0.0187653 -0.00294656 -0.283979 0.958642 +VERTEX_SE3:QUAT 116 -54.3409 222.086 -4.316 -0.0152045 -0.0101628 -0.285533 0.958195 +VERTEX_SE3:QUAT 117 -50.9682 219.773 -4.19892 -0.0145334 -0.0117568 -0.288268 0.957367 +VERTEX_SE3:QUAT 118 -47.522 217.372 -4.04825 -0.01133 0.00346051 -0.293088 0.956012 +VERTEX_SE3:QUAT 119 -44.2829 215.023 -4.02095 -0.00971294 0.00245782 -0.297009 0.954822 +VERTEX_SE3:QUAT 120 -40.6047 212.36 -3.99391 -0.0117863 0.00176211 -0.301247 0.953472 +VERTEX_SE3:QUAT 121 -37.0394 209.767 -3.94575 -0.0137655 0.00259781 -0.296927 0.954797 +VERTEX_SE3:QUAT 122 -33.4781 207.243 -3.88665 -0.015532 0.0028137 -0.290919 0.956618 +VERTEX_SE3:QUAT 123 -30.2042 204.92 -3.82684 -0.0124417 -0.0077438 -0.294287 0.955605 +VERTEX_SE3:QUAT 124 -26.6948 202.426 -3.69169 -0.012044 0.00115269 -0.304745 0.952357 +VERTEX_SE3:QUAT 125 -23.488 199.83 -3.67892 -0.00607349 0.00852672 -0.376268 0.926452 +VERTEX_SE3:QUAT 126 -21.0818 196.525 -3.67946 -0.0155107 0.00378113 -0.551471 0.834041 +VERTEX_SE3:QUAT 127 -20.5861 192.444 -3.61179 -0.0121058 -0.00146646 -0.758643 0.651393 +VERTEX_SE3:QUAT 128 -22.089 188.772 -3.53042 -0.00222958 -0.00136624 -0.870572 0.492034 +VERTEX_SE3:QUAT 129 -24.4163 185.572 -3.51903 0.00136286 -0.000463919 -0.893282 0.449495 +VERTEX_SE3:QUAT 130 -27.0415 182.121 -3.53094 0.000774692 0.00092351 -0.888574 0.458731 +VERTEX_SE3:QUAT 131 -29.4917 178.733 -3.52909 0.00154934 0.00087476 -0.88194 0.471359 +VERTEX_SE3:QUAT 132 -31.9096 175.212 -3.53025 -0.00231499 0.00504141 -0.883084 0.469183 +VERTEX_SE3:QUAT 133 -34.4282 171.704 -3.51132 -0.00968568 0.00343198 -0.885845 0.463868 +VERTEX_SE3:QUAT 134 -36.8986 168.294 -3.45241 -0.00717746 0.00321283 -0.884269 0.466912 +VERTEX_SE3:QUAT 135 -39.22 164.997 -3.39504 -0.00673386 0.00079725 -0.879625 0.475619 +VERTEX_SE3:QUAT 136 -41.53 161.568 -3.31911 -0.00634488 0.00225234 -0.877513 0.479506 +VERTEX_SE3:QUAT 137 -43.8947 158.223 -3.24528 0.000790195 0.00605002 -0.901481 0.432776 +VERTEX_SE3:QUAT 138 -47.0151 155.4 -3.2619 0.00176783 0.0101839 -0.963701 0.266782 +VERTEX_SE3:QUAT 139 -50.8444 154.126 -3.28768 0.000796335 0.0098962 -0.998304 0.0573654 +VERTEX_SE3:QUAT 140 -54.8101 154.506 -3.29043 0.0038855 -0.00432496 0.992679 0.120641 +VERTEX_SE3:QUAT 141 -58.8562 156.15 -3.2755 -0.0144903 0.00412316 0.973816 0.226839 +VERTEX_SE3:QUAT 142 -62.6291 158.334 -3.40115 -0.00942207 -0.00293608 0.963542 0.267376 +VERTEX_SE3:QUAT 143 -66.026 160.56 -3.46323 -0.0051245 -0.0027199 0.959627 0.281215 +VERTEX_SE3:QUAT 144 -69.5087 162.943 -3.49323 -0.00629217 -0.00121993 0.958533 0.284911 +VERTEX_SE3:QUAT 145 -73.0695 165.402 -3.52665 -0.00519625 -0.000463387 0.957358 0.288857 +VERTEX_SE3:QUAT 146 -76.649 167.919 -3.54768 -0.00340316 -0.000857405 0.95615 0.292857 +VERTEX_SE3:QUAT 147 -80.2874 170.501 -3.56919 -0.013005 -0.000101738 0.954913 0.296601 +VERTEX_SE3:QUAT 148 -83.5071 172.838 -3.67763 -0.0162914 0.000840188 0.954048 0.299211 +VERTEX_SE3:QUAT 149 -86.7675 175.222 -3.80167 -0.014214 -0.00178179 0.953322 0.301615 +VERTEX_SE3:QUAT 150 -90.4239 177.916 -3.9022 -0.0132517 -0.00464099 0.952595 0.303916 +VERTEX_SE3:QUAT 151 -93.9287 180.535 -3.96975 -0.0124698 -0.00477474 0.952002 0.305802 +VERTEX_SE3:QUAT 152 -97.2781 183.059 -4.02368 -0.0128138 -0.00379862 0.951413 0.307628 +VERTEX_SE3:QUAT 153 -100.787 185.74 -4.09511 -0.00703268 -0.0017022 0.950921 0.30935 +VERTEX_SE3:QUAT 154 -103.96 188.169 -4.12863 -0.00750698 3.99585e-05 0.951889 0.30635 +VERTEX_SE3:QUAT 155 -107.251 190.547 -4.15702 -0.0156176 0.00488469 0.96392 0.265689 +VERTEX_SE3:QUAT 156 -111.251 192.434 -4.29438 -0.0135294 0.00747559 0.992778 0.118968 +VERTEX_SE3:QUAT 157 -115.634 192.697 -4.39958 0.0138806 -0.00651553 -0.995579 0.0926645 +VERTEX_SE3:QUAT 158 -119.643 191.024 -4.49176 0.00889019 -0.00752277 -0.943086 0.332344 +VERTEX_SE3:QUAT 159 -122.263 187.898 -4.50572 -0.000840366 -0.0143776 -0.840708 0.541297 +VERTEX_SE3:QUAT 160 -123.241 183.538 -4.41255 -0.00225582 -0.0162299 -0.697961 0.715949 +VERTEX_SE3:QUAT 161 -122.548 179.478 -4.29159 -0.00257457 -0.0161194 -0.560333 0.828107 +VERTEX_SE3:QUAT 162 -120.453 175.68 -4.1556 -0.00117696 -0.0166255 -0.432096 0.901673 +VERTEX_SE3:QUAT 163 -117.543 172.696 -4.05378 -0.00464653 0.00320998 -0.334237 0.942472 +VERTEX_SE3:QUAT 164 -114.047 170.175 -4.06139 -0.00795477 -0.00170589 -0.271047 0.962532 +VERTEX_SE3:QUAT 165 -110.18 167.832 -4.01391 -0.0158251 -0.00126643 -0.266818 0.963616 +VERTEX_SE3:QUAT 166 -106.804 165.648 -3.95794 -0.0147733 -0.0017687 -0.277995 0.960467 +VERTEX_SE3:QUAT 167 -103.414 163.368 -3.89876 -0.014712 -0.00317733 -0.286751 0.957887 +VERTEX_SE3:QUAT 168 -99.8911 160.878 -3.82619 -0.0119812 -0.00690802 -0.296448 0.954949 +VERTEX_SE3:QUAT 169 -96.5223 158.397 -3.72903 -0.0102731 -0.0119824 -0.304768 0.952296 +VERTEX_SE3:QUAT 170 -93.1141 155.818 -3.59843 -0.00562824 -0.00649869 -0.30951 0.950857 +VERTEX_SE3:QUAT 171 -89.6036 153.123 -3.55053 -0.00320585 0.00315508 -0.3135 0.949578 +VERTEX_SE3:QUAT 172 -86.1994 150.469 -3.55534 -0.00811179 -0.000989241 -0.315714 0.948819 +VERTEX_SE3:QUAT 173 -82.763 147.791 -3.5123 -0.010082 0.000448162 -0.315709 0.948802 +VERTEX_SE3:QUAT 174 -79.3905 145.169 -3.47164 -0.0084676 -0.00238944 -0.312817 0.949773 +VERTEX_SE3:QUAT 175 -76.2311 142.726 -3.40596 -0.00843155 -0.00375543 -0.305699 0.952084 +VERTEX_SE3:QUAT 176 -72.6411 140.24 -3.3332 -0.0039988 -0.0107507 -0.247125 0.968916 +VERTEX_SE3:QUAT 177 -68.6898 138.467 -3.23437 0.00178026 0.00582779 -0.137289 0.990512 +VERTEX_SE3:QUAT 178 -64.6546 137.746 -3.27629 0.00127301 0.00738299 -0.0121681 0.999898 +VERTEX_SE3:QUAT 179 -60.4782 138.112 -3.30141 -0.00540142 0.00986943 0.131329 0.991275 +VERTEX_SE3:QUAT 180 -56.513 139.755 -3.35838 -0.010854 0.00786478 0.282968 0.959036 +VERTEX_SE3:QUAT 181 -53.2538 142.476 -3.41515 -0.00353902 -0.00336298 0.418026 0.908422 +VERTEX_SE3:QUAT 182 -50.7008 145.643 -3.40973 -0.00607777 -0.00675618 0.451436 0.892257 +VERTEX_SE3:QUAT 183 -48.229 149.002 -3.39862 -0.00730646 -0.00791235 0.465992 0.884723 +VERTEX_SE3:QUAT 184 -45.8601 152.311 -3.37023 -0.00502182 -0.0061661 0.468647 0.88335 +VERTEX_SE3:QUAT 185 -43.3405 155.834 -3.35117 -0.00669463 0.00135544 0.466469 0.884511 +VERTEX_SE3:QUAT 186 -40.7464 159.447 -3.40475 -0.0107275 0.00572488 0.465199 0.885123 +VERTEX_SE3:QUAT 187 -38.3528 162.779 -3.45663 -0.0116647 0.00602881 0.465965 0.884706 +VERTEX_SE3:QUAT 188 -36.0222 166.033 -3.51646 -0.0134377 0.00419882 0.465429 0.884973 +VERTEX_SE3:QUAT 189 -33.6572 169.32 -3.5704 -0.016997 0.00144684 0.467142 0.884018 +VERTEX_SE3:QUAT 190 -31.3927 172.651 -3.62906 -0.00748574 -0.00172375 0.521531 0.853198 +VERTEX_SE3:QUAT 191 -30.0732 176.456 -3.64457 -0.0014274 -0.000584052 0.678765 0.734354 +VERTEX_SE3:QUAT 192 -30.4439 180.482 -3.64562 0.0075713 0.00182446 0.821594 0.57002 +VERTEX_SE3:QUAT 193 -32.5021 184.038 -3.61159 0.021272 -0.00225944 0.912095 0.40942 +VERTEX_SE3:QUAT 194 -35.5851 186.907 -3.45121 0.0276237 -0.00482214 0.947264 0.319224 +VERTEX_SE3:QUAT 195 -38.9232 189.371 -3.21868 0.0245382 -0.00545567 0.956183 0.291688 +VERTEX_SE3:QUAT 196 -42.5069 191.854 -3.01768 0.0183065 -0.00595601 0.957101 0.289116 +VERTEX_SE3:QUAT 197 -45.8217 194.175 -2.87015 0.0213133 -0.00813503 0.956735 0.290064 +VERTEX_SE3:QUAT 198 -49.126 196.49 -2.69944 0.0195546 -0.00519822 0.956386 0.291404 +VERTEX_SE3:QUAT 199 -52.5463 198.905 -2.54234 0.0189023 -0.00503398 0.956064 0.292503 +VERTEX_SE3:QUAT 200 -55.9683 201.332 -2.37272 0.0158584 -0.00246026 0.955872 0.293346 +VERTEX_SE3:QUAT 201 -59.3284 203.726 -2.231 0.0162726 -0.00350237 0.955902 0.293212 +VERTEX_SE3:QUAT 202 -62.8661 206.236 -2.08723 0.0150405 -0.00455584 0.955991 0.292976 +VERTEX_SE3:QUAT 203 -66.2254 208.618 -1.94954 0.0155375 -0.00423644 0.956149 0.292436 +VERTEX_SE3:QUAT 204 -69.6298 211.024 -1.82385 0.0162858 -0.00492319 0.956272 0.291985 +VERTEX_SE3:QUAT 205 -72.9462 213.366 -1.68464 0.0126701 -0.00280612 0.956729 0.29069 +VERTEX_SE3:QUAT 206 -76.5482 215.866 -1.55217 0.00839272 -0.00193617 0.958218 0.28591 +VERTEX_SE3:QUAT 207 -79.9192 218.171 -1.43189 0.0104497 -0.00315769 0.958993 0.28322 +VERTEX_SE3:QUAT 208 -83.3153 220.526 -1.3178 0.00525217 -0.00282429 0.952892 0.303251 +VERTEX_SE3:QUAT 209 -86.4937 223.159 -1.31735 -0.0223349 0.00216524 0.924099 0.381494 +VERTEX_SE3:QUAT 210 -88.8434 226.755 -1.47678 -0.0198565 -0.00659218 0.817838 0.575069 +VERTEX_SE3:QUAT 211 -89.1615 231.131 -1.56114 -0.0232086 -0.00909532 0.630768 0.775571 +VERTEX_SE3:QUAT 212 -87.2401 234.783 -1.59971 -0.0253907 -0.000547221 0.399134 0.916541 +VERTEX_SE3:QUAT 213 -83.5074 237.005 -1.63577 -0.028624 -0.00557841 0.133427 0.990629 +VERTEX_SE3:QUAT 214 -79.4533 237.083 -1.57615 -0.0226586 -0.00972441 -0.0905223 0.995589 +VERTEX_SE3:QUAT 215 -75.7156 235.683 -1.44611 -0.0149372 -0.00120313 -0.23134 0.972757 +VERTEX_SE3:QUAT 216 -72.0419 233.391 -1.40248 -0.0147687 -0.00134466 -0.283001 0.959005 +VERTEX_SE3:QUAT 217 -68.7178 231.118 -1.37498 -0.0178846 -0.00223177 -0.287573 0.957589 +VERTEX_SE3:QUAT 218 -65.2279 228.722 -1.29986 -0.019195 0.0031241 -0.288132 0.957393 +VERTEX_SE3:QUAT 219 -61.6272 226.239 -1.23426 -0.0219675 -0.00149379 -0.287098 0.957648 +VERTEX_SE3:QUAT 220 -58.1403 223.845 -1.12914 -0.0208749 -0.00648291 -0.284529 0.958418 +VERTEX_SE3:QUAT 221 -54.7011 221.505 -1.02107 -0.0167358 -0.00939016 -0.281598 0.95934 +VERTEX_SE3:QUAT 222 -51.2855 219.212 -0.913239 -0.0129203 -0.00496769 -0.279206 0.960131 +VERTEX_SE3:QUAT 223 -47.8331 216.927 -0.816558 -0.0108771 0.00131374 -0.278159 0.960473 +VERTEX_SE3:QUAT 224 -44.4381 214.678 -0.773734 -0.0127681 -0.000842809 -0.280386 0.959802 +VERTEX_SE3:QUAT 225 -41.061 212.4 -0.730286 -0.0149504 -0.000555164 -0.284862 0.958452 +VERTEX_SE3:QUAT 226 -37.3497 209.808 -0.702365 -0.0151318 0.0018775 -0.297884 0.95448 +VERTEX_SE3:QUAT 227 -33.9863 207.275 -0.644008 -0.0162417 -0.000985789 -0.31896 0.947629 +VERTEX_SE3:QUAT 228 -30.8388 204.674 -0.545538 -0.0120813 -0.00255568 -0.32901 0.944246 +VERTEX_SE3:QUAT 229 -27.4239 201.951 -0.448651 -0.0109535 -0.00489582 -0.29569 0.955208 +VERTEX_SE3:QUAT 230 -23.8571 199.798 -0.409134 -0.00373855 0.00780037 -0.188748 0.981987 +VERTEX_SE3:QUAT 231 -19.8057 198.855 -0.450833 -0.00801832 0.00220013 0.00052786 0.999965 +VERTEX_SE3:QUAT 232 -15.5078 199.674 -0.467518 -0.0101789 0.00160587 0.217309 0.976049 +VERTEX_SE3:QUAT 233 -12.0588 202.079 -0.506696 -0.00894458 0.00287972 0.415084 0.909734 +VERTEX_SE3:QUAT 234 -9.91111 205.652 -0.56549 -0.0110094 0.00658454 0.591339 0.806321 +VERTEX_SE3:QUAT 235 -9.33017 209.776 -0.657457 -0.00801897 0.00639855 0.74213 0.670177 +VERTEX_SE3:QUAT 236 -10.511 213.95 -0.730298 0.00180983 0.00719391 0.864484 0.502605 +VERTEX_SE3:QUAT 237 -12.9549 217.12 -0.731431 -0.00204757 0.00691021 0.929956 0.367599 +VERTEX_SE3:QUAT 238 -16.0219 219.671 -0.793236 -0.00861311 0.00568285 0.952341 0.304861 +VERTEX_SE3:QUAT 239 -19.4705 222.112 -0.872778 -0.00901563 0.00244311 0.958117 0.286226 +VERTEX_SE3:QUAT 240 -23.0225 224.495 -0.929456 -0.0091914 0.00365691 0.960155 0.279292 +VERTEX_SE3:QUAT 241 -26.6164 226.874 -0.977938 -0.00461352 0.00269295 0.960952 0.276662 +VERTEX_SE3:QUAT 242 -30.1847 229.218 -1.02526 -0.00393817 0.00261061 0.961096 0.276173 +VERTEX_SE3:QUAT 243 -33.7902 231.609 -1.07037 -0.00610727 0.00478332 0.960202 0.279198 +VERTEX_SE3:QUAT 244 -37.4527 234.052 -1.12997 -0.0137632 0.00451387 0.959298 0.282023 +VERTEX_SE3:QUAT 245 -41.0609 236.502 -1.22464 -0.0152824 0.00605835 0.958721 0.283873 +VERTEX_SE3:QUAT 246 -44.7592 239.014 -1.33971 -0.0149851 0.00291115 0.958245 0.285539 +VERTEX_SE3:QUAT 247 -48.4226 241.529 -1.47595 -0.0106779 0.000358044 0.958114 0.286188 +VERTEX_SE3:QUAT 248 -52.0051 244.004 -1.55522 -0.00523362 -0.000740366 0.957212 0.289339 +VERTEX_SE3:QUAT 249 -55.5327 246.498 -1.58439 -0.0116254 0.00151921 0.955799 0.293788 +VERTEX_SE3:QUAT 250 -58.8847 248.909 -1.63346 -0.00851421 0.00446153 0.954502 0.298049 +VERTEX_SE3:QUAT 251 -62.2993 251.41 -1.68494 -0.00879328 0.0103286 0.95572 0.293964 +VERTEX_SE3:QUAT 252 -65.7184 253.592 -1.79781 -0.0141136 0.0134651 0.975753 0.218002 +VERTEX_SE3:QUAT 253 -69.8613 254.852 -1.90959 -0.0065485 0.0141542 0.999505 0.0273365 +VERTEX_SE3:QUAT 254 -74.02 254.362 -1.92825 0.00405176 -0.0147377 -0.982407 0.186129 +VERTEX_SE3:QUAT 255 -77.5828 252.139 -1.9045 0.00284858 -0.0117782 -0.919576 0.392726 +VERTEX_SE3:QUAT 256 -80.1407 248.717 -1.87401 -0.00114597 -0.0112374 -0.870628 0.491813 +VERTEX_SE3:QUAT 257 -82.2833 245.261 -1.81084 -0.00190227 -0.0121079 -0.86885 0.494923 +VERTEX_SE3:QUAT 258 -84.6469 241.549 -1.74302 -0.00264287 -0.0127994 -0.875713 0.482655 +VERTEX_SE3:QUAT 259 -87.1495 237.908 -1.67107 -0.00235194 -0.0133228 -0.884181 0.466948 +VERTEX_SE3:QUAT 260 -89.6268 234.553 -1.58837 0.0054306 -0.00805555 -0.891879 0.452169 +VERTEX_SE3:QUAT 261 -92.3941 231.073 -1.59157 0.00637307 -0.00858937 -0.897249 0.441395 +VERTEX_SE3:QUAT 262 -95.2082 227.637 -1.5914 0.00692326 -0.013075 -0.897875 0.440002 +VERTEX_SE3:QUAT 263 -97.9998 224.157 -1.57773 0.00508448 -0.0109858 -0.895869 0.444153 +VERTEX_SE3:QUAT 264 -100.664 220.768 -1.56076 0.00476992 -0.00849139 -0.893318 0.449319 +VERTEX_SE3:QUAT 265 -103.262 217.383 -1.55225 0.00441904 -0.0112357 -0.88888 0.457982 +VERTEX_SE3:QUAT 266 -105.814 213.911 -1.52719 0.0050204 -0.0131925 -0.88405 0.467179 +VERTEX_SE3:QUAT 267 -108.178 210.534 -1.49373 0.00304647 -0.0140946 -0.880697 0.473461 +VERTEX_SE3:QUAT 268 -110.555 207.083 -1.45604 -0.000806168 -0.0123655 -0.882199 0.470713 +VERTEX_SE3:QUAT 269 -113.009 203.649 -1.41762 0.0125926 -0.0083731 -0.883976 0.467287 +VERTEX_SE3:QUAT 270 -115.48 200.22 -1.45946 0.0102859 -0.0106614 -0.885665 0.464088 +VERTEX_SE3:QUAT 271 -117.877 196.963 -1.47672 0.0100075 -0.0122758 -0.886858 0.461771 +VERTEX_SE3:QUAT 272 -120.268 193.714 -1.4889 0.00926023 -0.010665 -0.88649 0.462532 +VERTEX_SE3:QUAT 273 -122.604 190.264 -1.49902 0.00674216 -0.00973665 -0.858835 0.512115 +VERTEX_SE3:QUAT 274 -124.174 186.442 -1.49013 0.00460767 -0.00992867 -0.772303 0.63516 +VERTEX_SE3:QUAT 275 -124.343 182.355 -1.45049 0.002777 -0.00827768 -0.643008 0.76581 +VERTEX_SE3:QUAT 276 -123 178.366 -1.38658 -0.00153118 -0.0169061 -0.489117 0.872053 +VERTEX_SE3:QUAT 277 -120.312 175.104 -1.24223 -0.00255562 -0.0143801 -0.348286 0.937274 +VERTEX_SE3:QUAT 278 -116.985 172.608 -1.15928 -0.0043563 -0.00330257 -0.282639 0.959211 +VERTEX_SE3:QUAT 279 -113.365 170.269 -1.11402 -0.00676367 0.0015949 -0.274239 0.961636 +VERTEX_SE3:QUAT 280 -109.669 167.837 -1.07101 -0.00860721 0.00201947 -0.283218 0.959015 +VERTEX_SE3:QUAT 281 -106.109 165.401 -1.0405 -0.0121348 -0.00281737 -0.287729 0.957631 +VERTEX_SE3:QUAT 282 -102.501 162.899 -0.967546 -0.0132257 -0.0104426 -0.289242 0.957108 +VERTEX_SE3:QUAT 283 -98.9408 160.4 -0.862978 -0.00809862 -0.0101059 -0.29061 0.956754 +VERTEX_SE3:QUAT 284 -95.4907 157.988 -0.747718 -0.0071577 -0.00428318 -0.2921 0.956351 +VERTEX_SE3:QUAT 285 -92.0099 155.52 -0.657838 -0.0036756 0.00101556 -0.293651 0.955905 +VERTEX_SE3:QUAT 286 -88.5607 153.041 -0.638587 -0.00318449 -0.00117279 -0.294555 0.955628 +VERTEX_SE3:QUAT 287 -85.0695 150.544 -0.63411 -0.00487 -0.00173229 -0.299782 0.953994 +VERTEX_SE3:QUAT 288 -81.4506 147.857 -0.602482 -0.00687371 0.00247983 -0.309567 0.95085 +VERTEX_SE3:QUAT 289 -78.0319 145.193 -0.554719 -0.00613922 0.000127919 -0.318008 0.948068 +VERTEX_SE3:QUAT 290 -74.8021 142.615 -0.489678 -0.00487353 -0.00481037 -0.317868 0.94811 +VERTEX_SE3:QUAT 291 -71.6171 140.2 -0.418602 -0.00215846 -0.00655171 -0.281595 0.959509 +VERTEX_SE3:QUAT 292 -67.8272 138.073 -0.402977 0.00110829 0.00293807 -0.189032 0.981966 +VERTEX_SE3:QUAT 293 -63.6344 136.876 -0.413043 -0.000583075 0.00204655 -0.0515556 0.998668 +VERTEX_SE3:QUAT 294 -59.5628 137.004 -0.394216 0.000876034 -0.000792344 0.117111 0.993118 +VERTEX_SE3:QUAT 295 -55.5981 138.588 -0.386019 -0.000284222 -0.0018938 0.295598 0.955311 +VERTEX_SE3:QUAT 296 -52.3934 141.441 -0.389358 0.00165513 0.00219694 0.454749 0.890616 +VERTEX_SE3:QUAT 297 -50.6301 145.174 -0.390843 0.000636154 0.00194286 0.653312 0.757086 +VERTEX_SE3:QUAT 298 -50.957 149.339 -0.398855 -0.00314475 0.000774484 0.82745 0.561531 +VERTEX_SE3:QUAT 299 -53.2109 152.678 -0.402812 0.000914761 -0.00202164 0.933791 0.357811 +VERTEX_SE3:QUAT 300 -56.6036 155.114 -0.379597 -0.00132204 -0.00239398 0.967221 0.253923 +VERTEX_SE3:QUAT 301 -60.1607 157.091 -0.434154 -0.0121647 -0.00427911 0.970355 0.241338 +VERTEX_SE3:QUAT 302 -64.0067 159.32 -0.531837 -0.0114584 -0.0044858 0.96632 0.257051 +VERTEX_SE3:QUAT 303 -67.4745 161.471 -0.592926 -0.00839556 -0.00603192 0.962252 0.271965 +VERTEX_SE3:QUAT 304 -70.9814 163.81 -0.606555 -0.00400812 -0.00450877 0.958624 0.284612 +VERTEX_SE3:QUAT 305 -74.4402 166.198 -0.632554 -0.00217684 -0.00595926 0.957762 0.287493 +VERTEX_SE3:QUAT 306 -77.9728 168.658 -0.652517 -0.00488026 -0.00152155 0.957495 0.288405 +VERTEX_SE3:QUAT 307 -81.5108 171.11 -0.668422 -0.0167285 0.000514133 0.95719 0.288978 +VERTEX_SE3:QUAT 308 -85.067 173.576 -0.764425 -0.0183352 -0.00250265 0.957077 0.289242 +VERTEX_SE3:QUAT 309 -88.6193 176.039 -0.883881 -0.0143252 -0.00543135 0.957167 0.28913 +VERTEX_SE3:QUAT 310 -92.2726 178.58 -0.995583 -0.0134253 -0.00675478 0.957095 0.289385 +VERTEX_SE3:QUAT 311 -95.7386 180.994 -1.06079 -0.01212 -0.00608875 0.956839 0.290301 +VERTEX_SE3:QUAT 312 -99.1773 183.391 -1.09609 -0.0130882 -0.00500686 0.956605 0.291052 +VERTEX_SE3:QUAT 313 -102.554 185.775 -1.14061 -0.00647433 -0.00542987 0.955962 0.293368 +VERTEX_SE3:QUAT 314 -105.853 188.166 -1.16474 -0.00318281 -0.00656927 0.950394 0.310962 +VERTEX_SE3:QUAT 315 -109.038 190.933 -1.20474 -0.0232546 -0.00621777 0.918527 0.394625 +VERTEX_SE3:QUAT 316 -111.417 194.384 -1.33033 -0.0238907 -0.00737308 0.844968 0.534233 +VERTEX_SE3:QUAT 317 -112.454 198.337 -1.41222 -0.0166829 -0.0101331 0.738501 0.67397 +VERTEX_SE3:QUAT 318 -111.99 202.287 -1.42505 -0.0194168 -0.00847291 0.577151 0.816363 +VERTEX_SE3:QUAT 319 -109.55 205.714 -1.45035 -0.0198226 -0.00538067 0.332491 0.942883 +VERTEX_SE3:QUAT 320 -105.661 207.392 -1.44562 -0.0202892 -0.00628691 0.0766019 0.996835 +VERTEX_SE3:QUAT 321 -101.549 207.06 -1.37254 -0.0196378 -0.0120971 -0.137751 0.990198 +VERTEX_SE3:QUAT 322 -97.9542 205.342 -1.23069 -0.016914 -0.0205881 -0.266508 0.963464 +VERTEX_SE3:QUAT 323 -94.5506 202.831 -0.996791 -0.0146029 -0.0367452 -0.323551 0.945384 +VERTEX_SE3:QUAT 324 -91.4631 200.308 -0.712673 -0.0130545 -0.03372 -0.320836 0.946444 +VERTEX_SE3:QUAT 325 -88.2107 197.731 -0.39792 -0.0114238 -0.027766 -0.314055 0.94893 +VERTEX_SE3:QUAT 326 -84.7263 195.077 -0.0987876 -0.0137373 -0.0291864 -0.306144 0.951438 +VERTEX_SE3:QUAT 327 -81.2197 192.498 0.179805 -0.0158776 -0.0336303 -0.297868 0.953882 +VERTEX_SE3:QUAT 328 -77.6248 189.93 0.457679 -0.0146078 -0.0367198 -0.292334 0.955499 +VERTEX_SE3:QUAT 329 -73.9796 187.369 0.777192 -0.013635 -0.029976 -0.292347 0.955745 +VERTEX_SE3:QUAT 330 -70.7107 185.059 1.05794 -0.0127517 -0.0238216 -0.291163 0.956292 +VERTEX_SE3:QUAT 331 -67.0601 182.507 1.33583 -0.0135024 -0.0259932 -0.288599 0.957002 +VERTEX_SE3:QUAT 332 -63.4246 179.999 1.5935 -0.0155551 -0.0302745 -0.283771 0.958288 +VERTEX_SE3:QUAT 333 -59.7109 177.536 1.85268 -0.0155898 -0.0339291 -0.27515 0.960676 +VERTEX_SE3:QUAT 334 -56.1982 175.279 2.14818 -0.012159 -0.0246319 -0.267105 0.963276 +VERTEX_SE3:QUAT 335 -52.5889 173.021 2.41951 -0.0153103 -0.0249686 -0.271129 0.962097 +VERTEX_SE3:QUAT 336 -49.12 170.687 2.70787 -0.00926834 -0.00671467 -0.307611 0.951443 +VERTEX_SE3:QUAT 337 -46 167.883 2.75048 -0.0101946 0.00604013 -0.416601 0.909012 +VERTEX_SE3:QUAT 338 -43.9279 164.268 2.75771 -0.0105284 0.00791593 -0.5842 0.811503 +VERTEX_SE3:QUAT 339 -43.4769 160.26 2.79141 -0.00864532 0.00428417 -0.737844 0.674902 +VERTEX_SE3:QUAT 340 -44.9089 156.278 2.839 0.00765133 0.00939638 -0.883288 0.468675 +VERTEX_SE3:QUAT 341 -48.21 153.554 2.764 0.00692764 0.0117049 -0.978124 0.207578 +VERTEX_SE3:QUAT 342 -52.1648 152.929 2.71122 -0.00188374 -0.0139753 0.999066 0.0408325 +VERTEX_SE3:QUAT 343 -55.9615 154.11 2.71402 0.00297868 -0.0106506 0.975091 0.22153 +VERTEX_SE3:QUAT 344 -59.6058 156.443 2.72835 -0.0168512 -0.00258865 0.953024 0.302414 +VERTEX_SE3:QUAT 345 -62.8163 158.957 2.62978 -0.0192782 -0.00450326 0.946237 0.322868 +VERTEX_SE3:QUAT 346 -66.221 161.709 2.50678 -0.0109642 -0.00784365 0.946759 0.321662 +VERTEX_SE3:QUAT 347 -69.5434 164.341 2.46488 -0.00264778 -0.00971138 0.949679 0.313062 +VERTEX_SE3:QUAT 348 -73.05 167.006 2.45388 -0.00333161 -0.00720285 0.952144 0.305548 +VERTEX_SE3:QUAT 349 -76.5034 169.573 2.45018 -0.0115676 -0.00593938 0.952876 0.303082 +VERTEX_SE3:QUAT 350 -80.0227 172.174 2.40564 -0.0165146 -0.00225046 0.953695 0.300313 +VERTEX_SE3:QUAT 351 -83.4676 174.678 2.30674 -0.0128343 -0.00278624 0.954401 0.298237 +VERTEX_SE3:QUAT 352 -86.9061 177.124 2.20248 -0.0138002 -0.00685653 0.955349 0.295077 +VERTEX_SE3:QUAT 353 -90.453 179.617 2.11938 -0.0179664 -0.00952603 0.956795 0.290053 +VERTEX_SE3:QUAT 354 -94.1664 182.176 2.02769 -0.0124764 -0.0105052 0.958466 0.284739 +VERTEX_SE3:QUAT 355 -97.742 184.598 1.99481 -0.0151619 -0.00548293 0.960049 0.279367 +VERTEX_SE3:QUAT 356 -101.208 186.892 1.92376 -0.0074559 -0.00681939 0.960348 0.278619 +VERTEX_SE3:QUAT 357 -104.655 189.207 1.89282 -0.00304142 -0.00682132 0.960275 0.278955 +VERTEX_SE3:QUAT 358 -108.142 191.414 1.86766 -0.023904 0.00422719 0.970578 0.239562 +VERTEX_SE3:QUAT 359 -112.195 193.077 1.69193 -0.0194736 0.00480302 0.995314 0.0945939 +VERTEX_SE3:QUAT 360 -116.634 193.17 1.5571 0.0124557 -0.00671138 -0.99431 0.105585 +VERTEX_SE3:QUAT 361 -120.607 191.597 1.47061 0.00840969 -0.00991303 -0.950855 0.309364 +VERTEX_SE3:QUAT 362 -123.483 188.586 1.44496 0.0106608 -0.0101496 -0.860471 0.509286 +VERTEX_SE3:QUAT 363 -124.797 184.592 1.43724 0.00654609 -0.00907558 -0.729864 0.683501 +VERTEX_SE3:QUAT 364 -124.303 180.286 1.47049 3.37506e-05 -0.0149612 -0.568579 0.822492 +VERTEX_SE3:QUAT 365 -122.137 176.53 1.58106 -0.00359846 -0.0160061 -0.414153 0.910059 +VERTEX_SE3:QUAT 366 -119.022 173.465 1.73521 0.00249711 -0.000862459 -0.330483 0.943808 +VERTEX_SE3:QUAT 367 -115.719 170.998 1.75396 -0.0055185 -0.00318932 -0.290677 0.9568 +VERTEX_SE3:QUAT 368 -112.178 168.617 1.78127 -0.00877695 -0.00849554 -0.279032 0.960204 +VERTEX_SE3:QUAT 369 -108.501 166.237 1.85717 -0.00814333 -0.00283025 -0.272981 0.961981 +VERTEX_SE3:QUAT 370 -105.132 164.051 1.91269 -0.00950703 -0.00623502 -0.278025 0.960507 +VERTEX_SE3:QUAT 371 -101.504 161.57 2.03321 -0.00536318 -0.00682756 -0.291318 0.956587 +VERTEX_SE3:QUAT 372 -98.0488 159.07 2.12473 -0.00654158 -0.00812415 -0.303471 0.952784 +VERTEX_SE3:QUAT 373 -94.5704 156.425 2.20305 -0.00404658 -0.00931765 -0.311449 0.950209 +VERTEX_SE3:QUAT 374 -91.1944 153.842 2.28506 -0.00352905 -0.00277529 -0.311637 0.950191 +VERTEX_SE3:QUAT 375 -87.8367 151.242 2.34345 -0.00097025 0.00288217 -0.311801 0.950143 +VERTEX_SE3:QUAT 376 -84.4429 148.626 2.36939 -0.00347637 0.000422552 -0.312358 0.949958 +VERTEX_SE3:QUAT 377 -81.1673 146.113 2.39449 -0.00699922 -0.000631248 -0.312591 0.949862 +VERTEX_SE3:QUAT 378 -77.9933 143.657 2.43799 -0.00643528 -0.00451321 -0.312343 0.949937 +VERTEX_SE3:QUAT 379 -74.6671 141.087 2.51555 -0.00293631 -0.00570447 -0.308014 0.95136 +VERTEX_SE3:QUAT 380 -71.3374 138.703 2.60036 0.000980478 0.0019644 -0.268175 0.963368 +VERTEX_SE3:QUAT 381 -67.6703 136.793 2.59507 0.00416493 0.00195877 -0.161251 0.986903 +VERTEX_SE3:QUAT 382 -63.3043 136.045 2.58831 -0.000565832 -0.00337269 0.0319045 0.999485 +VERTEX_SE3:QUAT 383 -59.3645 136.927 2.62252 -0.000470402 -0.00488875 0.218044 0.975927 +VERTEX_SE3:QUAT 384 -55.7664 139.289 2.65655 -0.00178209 -0.00364025 0.368978 0.929429 +VERTEX_SE3:QUAT 385 -52.9485 142.348 2.65759 -0.000106233 -0.00324699 0.449703 0.893172 +VERTEX_SE3:QUAT 386 -50.533 145.728 2.6821 -0.000491533 -0.00368745 0.474894 0.880035 +VERTEX_SE3:QUAT 387 -48.1156 149.229 2.72406 -0.00038865 -0.00468788 0.468086 0.883671 +VERTEX_SE3:QUAT 388 -45.6955 152.585 2.76738 0.00113062 -0.00974989 0.460646 0.88753 +VERTEX_SE3:QUAT 389 -43.2208 155.949 2.85052 -0.00762267 0.00524557 0.458763 0.888511 +VERTEX_SE3:QUAT 390 -40.6882 159.325 2.79457 -0.00379368 0.00329461 0.458338 0.888764 +VERTEX_SE3:QUAT 391 -38.132 162.749 2.77781 -0.00225386 0.00249098 0.457757 0.889071 +VERTEX_SE3:QUAT 392 -35.6086 166.136 2.76772 -0.00277026 0.000642839 0.458655 0.88861 +VERTEX_SE3:QUAT 393 -33.0769 169.538 2.76947 -0.00223859 0.000320409 0.460629 0.88759 +VERTEX_SE3:QUAT 394 -30.5842 172.925 2.7645 -0.00228765 0.00217904 0.465085 0.88526 +VERTEX_SE3:QUAT 395 -28.0935 176.409 2.75849 0.000451779 0.000930754 0.469782 0.882782 +VERTEX_SE3:QUAT 396 -25.6755 179.876 2.77101 -0.000166672 -0.00050354 0.473312 0.880894 +VERTEX_SE3:QUAT 397 -23.2855 183.368 2.77774 -0.000776062 -0.00441449 0.476438 0.879197 +VERTEX_SE3:QUAT 398 -20.9417 186.804 2.81078 -0.00704875 0.00839305 0.478838 0.877835 +VERTEX_SE3:QUAT 399 -18.6341 190.161 2.73898 -0.00543714 0.00517576 0.471776 0.881687 +VERTEX_SE3:QUAT 400 -16.211 193.578 2.69727 -0.00509178 0.0037905 0.462589 0.88655 +VERTEX_SE3:QUAT 401 -13.7977 196.816 2.67212 -0.00620461 0.00327658 0.455696 0.890108 +VERTEX_SE3:QUAT 402 -11.278 200.314 2.65382 -0.00688429 0.00180423 0.49227 0.870413 +VERTEX_SE3:QUAT 403 -9.39255 204.167 2.60593 -0.00442804 0.00519185 0.601107 0.79914 +VERTEX_SE3:QUAT 404 -8.74273 208.53 2.54592 -0.00452343 0.00366126 0.725503 0.688195 +VERTEX_SE3:QUAT 405 -9.43441 212.485 2.51774 0.00133376 0.00358444 0.82637 0.563114 +VERTEX_SE3:QUAT 406 -11.3869 216.059 2.51515 0.00605885 0.00377156 0.905539 0.424203 +VERTEX_SE3:QUAT 407 -14.4296 218.929 2.54145 -0.00802989 0.00586675 0.952114 0.305582 +VERTEX_SE3:QUAT 408 -18.053 221.324 2.5027 -0.0130142 0.00326717 0.964496 0.263755 +VERTEX_SE3:QUAT 409 -21.7584 223.624 2.42298 -0.00777672 -0.00213298 0.963478 0.267665 +VERTEX_SE3:QUAT 410 -25.4495 226.027 2.38962 -0.00260311 -0.000949982 0.959718 0.280953 +VERTEX_SE3:QUAT 411 -29.0745 228.511 2.36987 -0.00278261 5.61915e-06 0.957951 0.286918 +VERTEX_SE3:QUAT 412 -32.645 230.989 2.35302 -0.00982115 0.00270133 0.95702 0.289843 +VERTEX_SE3:QUAT 413 -36.0571 233.372 2.31493 -0.0132909 0.00213158 0.956247 0.29225 +VERTEX_SE3:QUAT 414 -39.3317 235.689 2.22751 -0.00909578 -0.000738249 0.955522 0.29478 +VERTEX_SE3:QUAT 415 -42.8631 238.212 2.15018 -0.0116883 -0.00237436 0.954812 0.296971 +VERTEX_SE3:QUAT 416 -46.4416 240.797 2.05872 -0.0112001 -0.0035479 0.954057 0.299396 +VERTEX_SE3:QUAT 417 -49.9383 243.351 1.99483 -0.0120723 -0.00710147 0.952667 0.303694 +VERTEX_SE3:QUAT 418 -53.4321 246.023 1.93893 -0.00957441 -0.00193326 0.949557 0.313441 +VERTEX_SE3:QUAT 419 -56.6034 248.501 1.89034 -0.00359507 -0.00358986 0.948151 0.31778 +VERTEX_SE3:QUAT 420 -59.9421 251.172 1.8627 -0.00205752 0.00165256 0.950691 0.310128 +VERTEX_SE3:QUAT 421 -63.4346 253.55 1.8341 -0.0175884 0.0112658 0.973686 0.226934 +VERTEX_SE3:QUAT 422 -67.335 254.967 1.70612 -0.0115913 0.0101079 0.996562 0.0814045 +VERTEX_SE3:QUAT 423 -71.5771 255.013 1.64053 0.00501198 -0.00589511 -0.994906 0.10051 +VERTEX_SE3:QUAT 424 -75.4764 253.641 1.62563 0.00616402 -0.0124987 -0.959527 0.281273 +VERTEX_SE3:QUAT 425 -78.6429 250.541 1.65243 0.00520205 -0.011541 -0.860175 0.509842 +VERTEX_SE3:QUAT 426 -79.7959 246.382 1.69222 -0.000639222 -0.00842205 -0.704227 0.709924 +VERTEX_SE3:QUAT 427 -79.0221 242.283 1.7656 -0.00547106 -0.0155387 -0.54368 0.839131 +VERTEX_SE3:QUAT 428 -76.7418 238.538 1.89662 -0.010055 -0.015682 -0.423198 0.905846 +VERTEX_SE3:QUAT 429 -73.8721 235.55 2.02875 -0.00607566 0.00312364 -0.345559 0.938372 +VERTEX_SE3:QUAT 430 -70.4265 232.758 2.04904 -0.00764365 0.00605944 -0.315203 0.948974 +VERTEX_SE3:QUAT 431 -67.1081 230.223 2.04932 -0.0131183 0.000831662 -0.309991 0.950649 +VERTEX_SE3:QUAT 432 -63.6922 227.656 2.0674 -0.0150357 0.000162351 -0.305646 0.952026 +VERTEX_SE3:QUAT 433 -60.1812 225.047 2.1237 -0.0174768 -0.0081558 -0.300794 0.953494 +VERTEX_SE3:QUAT 434 -56.5957 222.448 2.25038 -0.010653 -0.00154124 -0.296898 0.954848 +VERTEX_SE3:QUAT 435 -53.0974 219.939 2.32312 -0.00961682 -0.00158833 -0.29381 0.955814 +VERTEX_SE3:QUAT 436 -49.6756 217.507 2.38422 -0.0094586 -0.00368273 -0.290404 0.95685 +VERTEX_SE3:QUAT 437 -46.2084 215.087 2.42384 -0.00924696 -0.00237621 -0.287766 0.957653 +VERTEX_SE3:QUAT 438 -42.7279 212.698 2.47583 -0.00883308 0.00569184 -0.285268 0.95839 +VERTEX_SE3:QUAT 439 -39.185 210.272 2.49116 -0.0084659 0.00518912 -0.283346 0.958966 +VERTEX_SE3:QUAT 440 -35.8011 208.002 2.49471 -0.0114797 0.000379706 -0.277669 0.960608 +VERTEX_SE3:QUAT 441 -32.3954 205.785 2.53557 -0.0120162 -0.00705069 -0.275678 0.961149 +VERTEX_SE3:QUAT 442 -28.8835 203.418 2.61324 -0.00940785 -0.00580112 -0.297421 0.954683 +VERTEX_SE3:QUAT 443 -25.707 200.934 2.7022 -0.0038525 0.0110042 -0.349585 0.936832 +VERTEX_SE3:QUAT 444 -22.8632 197.827 2.65916 -0.0112966 0.00917426 -0.465345 0.88501 +VERTEX_SE3:QUAT 445 -21.1627 194.024 2.67131 -0.0105268 0.00499592 -0.616666 0.787138 +VERTEX_SE3:QUAT 446 -21.1499 189.735 2.72342 -0.00931657 0.00443335 -0.788895 0.614441 +VERTEX_SE3:QUAT 447 -23.2027 186.099 2.75279 0.0017248 0.00972111 -0.922715 0.385358 +VERTEX_SE3:QUAT 448 -26.8821 183.999 2.72959 0.00327403 0.00871569 -0.991511 0.129685 +VERTEX_SE3:QUAT 449 -31.1879 183.915 2.72009 -0.00153354 -0.00917053 0.9944 0.105271 +VERTEX_SE3:QUAT 450 -34.8687 185.552 2.72701 0.0132167 -0.0072898 0.963788 0.266241 +VERTEX_SE3:QUAT 451 -38.2822 187.991 2.86836 0.025743 -0.00950193 0.950232 0.310332 +VERTEX_SE3:QUAT 452 -41.6677 190.679 3.07894 0.0216341 -0.00239517 0.948664 0.315535 +VERTEX_SE3:QUAT 453 -45.025 193.26 3.26455 0.0197034 -0.0079213 0.949542 0.31292 +VERTEX_SE3:QUAT 454 -48.4433 195.898 3.45772 0.0218243 -0.00640641 0.950238 0.310692 +VERTEX_SE3:QUAT 455 -51.8017 198.443 3.6346 0.0244326 -0.0102332 0.950751 0.308823 +VERTEX_SE3:QUAT 456 -55.0554 200.909 3.80757 0.0219914 -0.00811564 0.951512 0.306716 +VERTEX_SE3:QUAT 457 -58.6037 203.562 3.9944 0.0192353 -0.00549428 0.952531 0.303783 +VERTEX_SE3:QUAT 458 -62.2699 206.264 4.19976 0.0144964 -0.0049657 0.953528 0.300913 +VERTEX_SE3:QUAT 459 -65.5835 208.677 4.32866 0.0218386 -0.00785024 0.954266 0.298056 +VERTEX_SE3:QUAT 460 -68.9574 211.109 4.49037 0.0235036 -0.0078822 0.955113 0.295201 +VERTEX_SE3:QUAT 461 -72.2758 213.48 4.68996 0.0167787 -0.00528676 0.956442 0.291392 +VERTEX_SE3:QUAT 462 -75.9909 216.07 4.89942 0.0112186 -0.00635036 0.956915 0.290081 +VERTEX_SE3:QUAT 463 -79.436 218.548 5.07617 0.0130212 -0.00765854 0.952522 0.304096 +VERTEX_SE3:QUAT 464 -82.7397 221.196 5.2403 0.00746376 -0.00550443 0.934645 0.355461 +VERTEX_SE3:QUAT 465 -85.5043 224.22 5.25897 -0.0163893 -0.00560799 0.894517 0.446698 +VERTEX_SE3:QUAT 466 -87.4323 227.752 5.18753 -0.0170193 -0.00468278 0.819441 0.572891 +VERTEX_SE3:QUAT 467 -88.0105 231.985 5.12855 -0.0136485 -0.00872093 0.670765 0.741493 +VERTEX_SE3:QUAT 468 -86.5873 235.735 5.10435 -0.0184223 0.00253525 0.458658 0.888418 +VERTEX_SE3:QUAT 469 -83.3879 238.29 5.05521 -0.0250867 -0.000263937 0.199128 0.979652 +VERTEX_SE3:QUAT 470 -79.2248 238.734 5.07152 -0.0205599 -0.00694596 -0.0754488 0.996913 +VERTEX_SE3:QUAT 471 -75.4488 237.199 5.16717 -0.01235 -0.00703814 -0.261777 0.965024 +VERTEX_SE3:QUAT 472 -71.9609 234.569 5.19819 -0.0101845 0.00246725 -0.335983 0.94181 +VERTEX_SE3:QUAT 473 -68.784 231.746 5.20018 -0.0112367 0.00238068 -0.351877 0.935976 +VERTEX_SE3:QUAT 474 -65.5001 228.731 5.24209 -0.0128384 0.00764916 -0.355541 0.934541 +VERTEX_SE3:QUAT 475 -62.1905 225.656 5.27341 -0.0122228 0.00154467 -0.3516 0.936069 +VERTEX_SE3:QUAT 476 -58.8167 222.638 5.33831 -0.014069 -0.00401392 -0.340899 0.939986 +VERTEX_SE3:QUAT 477 -55.4312 219.744 5.40299 -0.013203 -0.0092191 -0.328758 0.944277 +VERTEX_SE3:QUAT 478 -52.0739 217.023 5.49231 -0.0100096 -0.00471871 -0.316858 0.948408 +VERTEX_SE3:QUAT 479 -48.5364 214.315 5.56339 -0.00746258 0.00765076 -0.305147 0.952245 +VERTEX_SE3:QUAT 480 -45.199 211.871 5.57121 -0.00870846 0.00737353 -0.300088 0.953843 +VERTEX_SE3:QUAT 481 -41.9524 209.486 5.56579 -0.0120389 0.00222484 -0.30459 0.952405 +VERTEX_SE3:QUAT 482 -38.5155 206.879 5.56519 -0.0146858 -0.000365076 -0.312917 0.949667 +VERTEX_SE3:QUAT 483 -35.1338 204.237 5.61606 -0.0120094 0.00366602 -0.316129 0.948633 +VERTEX_SE3:QUAT 484 -31.7912 201.618 5.66635 -0.00895743 0.000850969 -0.314963 0.949061 +VERTEX_SE3:QUAT 485 -28.499 199.067 5.71822 -0.00827847 0.00442225 -0.309142 0.950969 +VERTEX_SE3:QUAT 486 -25.1112 196.595 5.69021 -0.00886873 0.00688659 -0.284546 0.958597 +VERTEX_SE3:QUAT 487 -21.5924 194.526 5.67199 -0.00556781 0.00425989 -0.184632 0.982783 +VERTEX_SE3:QUAT 488 -17.4396 193.674 5.66493 -0.00233894 0.00580585 0.0272939 0.999608 +VERTEX_SE3:QUAT 489 -13.4192 194.746 5.62601 -0.00335038 0.00117148 0.266438 0.963845 +VERTEX_SE3:QUAT 490 -10.3773 197.606 5.61828 -0.00479878 0.00162497 0.488287 0.872668 +VERTEX_SE3:QUAT 491 -8.67394 201.695 5.57869 -0.00895272 0.00856603 0.626179 0.779581 +VERTEX_SE3:QUAT 492 -8.19806 206.076 5.49659 -0.00660199 0.0070677 0.726156 0.687462 +VERTEX_SE3:QUAT 493 -8.85207 210.118 5.43704 -0.000333396 0.00672944 0.813986 0.580846 +VERTEX_SE3:QUAT 494 -10.5968 213.77 5.4243 0.00354707 0.00847936 0.889233 0.457362 +VERTEX_SE3:QUAT 495 -13.2749 216.83 5.45044 -0.00445516 0.00822143 0.93382 0.35762 +VERTEX_SE3:QUAT 496 -16.4945 219.493 5.37471 -0.00471915 0.00510385 0.950746 0.309892 +VERTEX_SE3:QUAT 497 -20.0181 222.014 5.30918 -0.00257354 0.000440128 0.957645 0.287939 +VERTEX_SE3:QUAT 498 -23.3678 224.276 5.30637 -0.00315193 -0.000361256 0.96065 0.277745 +VERTEX_SE3:QUAT 499 -27.1916 226.75 5.30926 -0.00386111 0.00100417 0.961992 0.273047 +VERTEX_SE3:QUAT 500 -30.7469 229.026 5.28998 0.000672035 0.00180642 0.962885 0.269906 +VERTEX_SE3:QUAT 501 -34.2914 231.276 5.27928 0.000844947 0.00110405 0.962717 0.270508 +VERTEX_SE3:QUAT 502 -38.084 233.695 5.27253 -0.00935606 0.0033968 0.962492 0.271128 +VERTEX_SE3:QUAT 503 -41.7555 236.055 5.21648 -0.0173603 0.00417402 0.961763 0.273301 +VERTEX_SE3:QUAT 504 -45.3807 238.408 5.11135 -0.0127346 0.00051704 0.961063 0.276034 +VERTEX_SE3:QUAT 505 -48.7783 240.653 5.0331 -0.00696207 -0.00102895 0.960324 0.278796 +VERTEX_SE3:QUAT 506 -52.5654 243.175 4.97639 1.56475e-05 -0.00352155 0.959678 0.281079 +VERTEX_SE3:QUAT 507 -56.1553 245.607 4.98303 -0.00544184 0.000976829 0.959364 0.282116 +VERTEX_SE3:QUAT 508 -59.6764 248.003 4.97979 -0.00172519 0.00320822 0.959809 0.280631 +VERTEX_SE3:QUAT 509 -63.2117 250.276 4.99759 -0.00897598 0.00783335 0.967388 0.253019 +VERTEX_SE3:QUAT 510 -66.8739 252.128 4.90671 -0.00925193 0.0110912 0.984771 0.173257 +VERTEX_SE3:QUAT 511 -70.919 253.188 4.83415 -0.0033647 0.0120367 0.9986 0.0513968 +VERTEX_SE3:QUAT 512 -75.082 253.098 4.81742 0.00368276 -0.0139761 -0.993656 0.111532 +VERTEX_SE3:QUAT 513 -79.1186 251.565 4.81944 0.00508036 -0.0122137 -0.961228 0.275439 +VERTEX_SE3:QUAT 514 -82.5005 248.811 4.82175 0.000590688 -0.00991965 -0.914664 0.404093 +VERTEX_SE3:QUAT 515 -85.2555 245.286 4.87138 -0.00321264 -0.00853905 -0.877528 0.479438 +VERTEX_SE3:QUAT 516 -87.6411 241.511 4.95345 -0.00404555 -0.0115609 -0.868054 0.496318 +VERTEX_SE3:QUAT 517 -89.9624 237.769 5.05701 9.56066e-05 -0.00496159 -0.870864 0.491499 +VERTEX_SE3:QUAT 518 -92.441 233.931 5.05292 0.00500425 -0.00533459 -0.876163 0.481959 +VERTEX_SE3:QUAT 519 -94.695 230.605 5.04535 0.00352602 -0.00726827 -0.880967 0.473109 +VERTEX_SE3:QUAT 520 -97.0866 227.207 5.06306 0.00476552 -0.00733224 -0.884958 0.465588 +VERTEX_SE3:QUAT 521 -99.4902 223.9 5.06854 0.00156958 -0.00586681 -0.888711 0.458427 +VERTEX_SE3:QUAT 522 -101.961 220.63 5.10906 0.00567267 -0.00285939 -0.891146 0.453672 +VERTEX_SE3:QUAT 523 -104.564 217.243 5.09554 0.00295198 -0.00575134 -0.892521 0.45096 +VERTEX_SE3:QUAT 524 -107.141 213.911 5.11304 0.00220726 -0.00649388 -0.89327 0.449469 +VERTEX_SE3:QUAT 525 -109.664 210.67 5.15103 0.00247917 -0.00644378 -0.892962 0.450079 +VERTEX_SE3:QUAT 526 -112.396 207.091 5.19023 0.00309351 -0.00175772 -0.892013 0.451997 +VERTEX_SE3:QUAT 527 -114.989 203.697 5.16235 0.00882196 0.00110042 -0.890489 0.454919 +VERTEX_SE3:QUAT 528 -117.533 200.271 5.11083 0.00799938 -0.000720801 -0.886642 0.462387 +VERTEX_SE3:QUAT 529 -119.994 196.75 5.0725 0.00636465 -0.0017409 -0.877223 0.480038 +VERTEX_SE3:QUAT 530 -122.252 193.265 5.05174 0.00249416 -0.00380944 -0.86464 0.502371 +VERTEX_SE3:QUAT 531 -124.152 189.548 5.05409 0.00872581 -0.005307 -0.817801 0.575411 +VERTEX_SE3:QUAT 532 -125.135 185.464 5.04483 0.00351114 -0.00378759 -0.73306 0.680144 +VERTEX_SE3:QUAT 533 -124.941 181.326 5.06358 0.00418013 -0.00941095 -0.616543 0.787254 +VERTEX_SE3:QUAT 534 -123.277 177.343 5.1344 0.00291059 -0.0120177 -0.467974 0.883656 +VERTEX_SE3:QUAT 535 -120.344 174.095 5.24276 0.00229957 -0.00198655 -0.340867 0.940107 +VERTEX_SE3:QUAT 536 -116.613 171.352 5.25995 -0.00563088 -0.00192689 -0.285037 0.958498 +VERTEX_SE3:QUAT 537 -113.194 169.096 5.27317 -0.00631826 -0.00369264 -0.273512 0.961841 +VERTEX_SE3:QUAT 538 -109.682 166.862 5.30571 -0.00584362 0.0044776 -0.270566 0.962673 +VERTEX_SE3:QUAT 539 -106.064 164.562 5.30944 -0.00831169 -0.00319716 -0.270365 0.962717 +VERTEX_SE3:QUAT 540 -102.453 162.244 5.38751 -0.0067482 -0.0054988 -0.270977 0.962546 +VERTEX_SE3:QUAT 541 -98.9195 159.96 5.44271 -0.0064656 -0.0101981 -0.272747 0.96201 +VERTEX_SE3:QUAT 542 -95.3487 157.635 5.52018 -0.00598782 -0.00924448 -0.276558 0.960934 +VERTEX_SE3:QUAT 543 -91.8365 155.292 5.60924 0.00222092 0.00447444 -0.281111 0.959662 +VERTEX_SE3:QUAT 544 -88.3153 152.905 5.59851 0.00111049 0.00374513 -0.285688 0.958315 +VERTEX_SE3:QUAT 545 -84.8092 150.488 5.5842 -0.0033632 -0.000670416 -0.290562 0.95685 +VERTEX_SE3:QUAT 546 -81.3068 148.01 5.58097 -0.00357759 -0.000562305 -0.296242 0.955106 +VERTEX_SE3:QUAT 547 -78.0263 145.62 5.60691 -0.00551492 -0.00324403 -0.303139 0.952925 +VERTEX_SE3:QUAT 548 -74.4878 142.952 5.68468 0.0020073 -0.000198726 -0.302424 0.953171 +VERTEX_SE3:QUAT 549 -71.1205 140.626 5.73776 0.00536062 -0.00135867 -0.256572 0.966509 +VERTEX_SE3:QUAT 550 -67.3805 138.778 5.73611 0.00610922 0.00443292 -0.163611 0.986496 +VERTEX_SE3:QUAT 551 -63.0363 137.864 5.72035 0.00243532 -0.000665746 -0.00173004 0.999995 +VERTEX_SE3:QUAT 552 -58.8779 138.552 5.765 0.00141159 -0.00130962 0.202547 0.979271 +VERTEX_SE3:QUAT 553 -55.3568 141.132 5.7835 0.00481946 -0.00342991 0.453604 0.891184 +VERTEX_SE3:QUAT 554 -53.7576 144.897 5.82523 -0.00231219 -0.00235791 0.660838 0.750522 +VERTEX_SE3:QUAT 555 -54.1089 148.961 5.83096 0.0041883 -0.00297469 0.822493 0.568752 +VERTEX_SE3:QUAT 556 -56.3017 152.49 5.86642 0.00639998 -0.0037946 0.92382 0.382756 +VERTEX_SE3:QUAT 557 -59.7528 155.242 5.91642 -0.0153351 -0.000556262 0.960033 0.279465 +VERTEX_SE3:QUAT 558 -63.3852 157.489 5.82546 -0.0157764 -0.00398701 0.965561 0.259667 +VERTEX_SE3:QUAT 559 -66.8158 159.598 5.72196 -0.00670912 -0.00881499 0.963848 0.266223 +VERTEX_SE3:QUAT 560 -70.2614 161.797 5.69259 -0.00333036 -0.00758612 0.961677 0.27406 +VERTEX_SE3:QUAT 561 -73.7603 164.121 5.70744 -0.00867844 -0.00632922 0.958862 0.283669 +VERTEX_SE3:QUAT 562 -77.31 166.585 5.69727 -0.00836142 -0.00442095 0.955794 0.293884 +VERTEX_SE3:QUAT 563 -80.7991 169.114 5.66161 -0.00345328 -0.00370538 0.953743 0.300582 +VERTEX_SE3:QUAT 564 -84.3136 171.691 5.59942 -0.00670301 -0.00455367 0.953538 0.301165 +VERTEX_SE3:QUAT 565 -87.9245 174.331 5.53465 -0.0139625 -0.00496672 0.954206 0.298782 +VERTEX_SE3:QUAT 566 -91.4473 176.856 5.46425 -0.0189026 -0.00459952 0.955629 0.293931 +VERTEX_SE3:QUAT 567 -94.9934 179.335 5.3596 -0.012107 -0.00816251 0.95748 0.288131 +VERTEX_SE3:QUAT 568 -98.3745 181.644 5.30916 -0.000786709 -0.0105756 0.959454 0.281664 +VERTEX_SE3:QUAT 569 -101.998 184.065 5.30499 -0.00411241 -0.00877593 0.958489 0.284964 +VERTEX_SE3:QUAT 570 -105.35 186.458 5.3212 -0.00425006 -0.00624126 0.950521 0.310569 +VERTEX_SE3:QUAT 571 -108.375 189.039 5.33479 -0.0197191 -0.00304721 0.925961 0.377092 +VERTEX_SE3:QUAT 572 -111.007 192.408 5.21327 -0.0201435 -0.00963591 0.867004 0.4978 +VERTEX_SE3:QUAT 573 -112.501 196.467 5.12775 -0.0145079 -0.0123482 0.773622 0.633361 +VERTEX_SE3:QUAT 574 -112.642 200.468 5.11816 -0.014605 -0.0113196 0.669181 0.742869 +VERTEX_SE3:QUAT 575 -111.538 204.382 5.14109 -0.0155505 -0.00422974 0.551583 0.833964 +VERTEX_SE3:QUAT 576 -109.335 208.033 5.10624 -0.0172055 -0.00367778 0.463496 0.885924 +VERTEX_SE3:QUAT 577 -106.607 211.494 5.08081 -0.0165509 -0.00201552 0.438688 0.898485 +VERTEX_SE3:QUAT 578 -104.049 214.625 5.06055 -0.0157443 -0.00299467 0.440193 0.89776 +VERTEX_SE3:QUAT 579 -101.505 217.743 5.04816 -0.0112918 -0.00358525 0.443017 0.896435 +VERTEX_SE3:QUAT 580 -98.7553 221.221 5.032 -0.0138608 -0.00240053 0.446354 0.894746 +VERTEX_SE3:QUAT 581 -96.2671 224.365 5.01987 -0.0127866 -0.00350108 0.448511 0.893679 +VERTEX_SE3:QUAT 582 -93.6117 227.818 5.00569 -0.0134493 -0.00320643 0.454789 0.890492 +VERTEX_SE3:QUAT 583 -90.9864 231.304 5.00365 -0.0139996 -0.00430271 0.45476 0.890494 +VERTEX_SE3:QUAT 584 -88.4194 234.47 5.01267 -0.0207164 -0.000785451 0.403343 0.914814 +VERTEX_SE3:QUAT 585 -85.2297 237.018 4.9792 -0.0201471 0.00446217 0.261356 0.965022 +VERTEX_SE3:QUAT 586 -81.4819 238.374 4.9454 -0.0237063 -0.00116967 0.0907019 0.995595 +VERTEX_SE3:QUAT 587 -77.3892 238.336 4.98361 -0.0214996 -0.00770772 -0.0863751 0.996001 +VERTEX_SE3:QUAT 588 -73.5312 236.935 5.08732 -0.0129837 0.001474 -0.226013 0.974037 +VERTEX_SE3:QUAT 589 -69.7572 234.468 5.09593 -0.0103662 0.00504069 -0.314943 0.94904 +VERTEX_SE3:QUAT 590 -66.5674 231.857 5.07706 -0.0151685 0.000136061 -0.331489 0.943337 +VERTEX_SE3:QUAT 591 -63.5229 229.31 5.12374 -0.0155038 0.0080545 -0.330843 0.943524 +VERTEX_SE3:QUAT 592 -60.1686 226.527 5.14867 -0.0174897 0.00148289 -0.32813 0.944469 +VERTEX_SE3:QUAT 593 -56.7255 223.712 5.22736 -0.01458 -0.00267726 -0.324124 0.945898 +VERTEX_SE3:QUAT 594 -53.4413 221.055 5.2955 -0.0156207 -0.00880777 -0.319846 0.9473 +VERTEX_SE3:QUAT 595 -50.0913 218.413 5.39039 -0.0113825 -0.00608889 -0.31587 0.948715 +VERTEX_SE3:QUAT 596 -46.7886 215.849 5.46713 -0.00750877 0.006653 -0.311834 0.950084 +VERTEX_SE3:QUAT 597 -43.474 213.304 5.47963 -0.00717904 0.0056312 -0.311563 0.950182 +VERTEX_SE3:QUAT 598 -40.2592 210.82 5.477 -0.0104 0.00136073 -0.314003 0.949364 +VERTEX_SE3:QUAT 599 -36.7369 208.07 5.49012 -0.0112163 0.000811 -0.314111 0.94932 +VERTEX_SE3:QUAT 600 -33.3645 205.45 5.52591 -0.0129278 0.00038546 -0.314027 0.949326 +VERTEX_SE3:QUAT 601 -30.1665 202.951 5.59534 -0.0126588 0.000448268 -0.324874 0.945673 +VERTEX_SE3:QUAT 602 -26.9275 200.089 5.67045 -0.0101221 0.00461729 -0.376787 0.926233 +VERTEX_SE3:QUAT 603 -24.2609 196.785 5.66331 -0.0148277 0.00949332 -0.48956 0.871792 +VERTEX_SE3:QUAT 604 -22.7002 192.807 5.68503 -0.0154412 0.00697302 -0.625907 0.779714 +VERTEX_SE3:QUAT 605 -22.5582 188.504 5.75845 -0.011326 0.0045366 -0.749327 0.662087 +VERTEX_SE3:QUAT 606 -23.865 184.314 5.79253 -0.00259589 0.00833138 -0.839084 0.543932 +VERTEX_SE3:QUAT 607 -25.9224 180.829 5.79555 -0.00228145 0.0064851 -0.877277 0.479935 +VERTEX_SE3:QUAT 608 -28.3417 177.381 5.80816 -0.00289205 0.00571303 -0.885545 0.46451 +VERTEX_SE3:QUAT 609 -30.9588 173.887 5.82614 -0.00209233 0.00278713 -0.891479 0.453048 +VERTEX_SE3:QUAT 610 -33.6613 170.379 5.86179 -0.00157593 0.00472976 -0.893582 0.448873 +VERTEX_SE3:QUAT 611 -36.3941 166.904 5.87844 -0.00384831 0.00291149 -0.894502 0.447038 +VERTEX_SE3:QUAT 612 -39.1705 163.39 5.9112 -0.00442156 0.00287131 -0.894394 0.447249 +VERTEX_SE3:QUAT 613 -41.8131 160.019 5.94855 -0.00375404 0.00133415 -0.894003 0.448042 +VERTEX_SE3:QUAT 614 -44.393 156.727 6.01112 0.00273941 0.00409795 -0.893049 0.449933 +VERTEX_SE3:QUAT 615 -47.0333 153.301 5.97643 0.00446068 0.00501364 -0.892088 0.451812 +VERTEX_SE3:QUAT 616 -49.6189 149.929 5.94121 0.00364787 0.00487347 -0.891191 0.453587 +VERTEX_SE3:QUAT 617 -52.2215 146.59 5.91483 0.00315873 0.00400293 -0.897608 0.440764 +VERTEX_SE3:QUAT 618 -54.9717 143.486 5.90256 0.00218537 0.00665266 -0.922046 0.387018 +VERTEX_SE3:QUAT 619 -58.2548 140.922 5.88162 0.00246114 0.00895444 -0.963271 0.268372 +VERTEX_SE3:QUAT 620 -62.1588 139.394 5.85875 -0.00137593 0.011151 -0.993299 0.115023 +VERTEX_SE3:QUAT 621 -66.3 139.166 5.87054 0.00267061 -0.0139613 0.998684 0.0492827 +VERTEX_SE3:QUAT 622 -70.5567 140.41 5.91691 -0.0140507 -0.00668012 0.979083 0.202867 +VERTEX_SE3:QUAT 623 -74.0383 142.487 5.84642 -0.00761149 -0.0014219 0.957131 0.289551 +VERTEX_SE3:QUAT 624 -77.4553 145.056 5.77463 -0.00504273 0.000440198 0.95017 0.31169 +VERTEX_SE3:QUAT 625 -81.0392 147.853 5.74242 -0.0011049 -0.00154083 0.949133 0.31487 +VERTEX_SE3:QUAT 626 -84.5892 150.618 5.75598 -0.00715529 -0.00149171 0.949338 0.314172 +VERTEX_SE3:QUAT 627 -87.7517 153.075 5.74515 -0.00491131 -0.00483944 0.949769 0.312876 +VERTEX_SE3:QUAT 628 -90.9327 155.545 5.73898 -0.00332378 -0.00494488 0.950577 0.310431 +VERTEX_SE3:QUAT 629 -94.4186 158.206 5.68862 -0.0103227 0.00202411 0.951454 0.30761 +VERTEX_SE3:QUAT 630 -97.6402 160.642 5.63354 -0.0151157 0.00350176 0.952276 0.304843 +VERTEX_SE3:QUAT 631 -101.163 163.271 5.54488 -0.0159101 0.00756166 0.953346 0.301366 +VERTEX_SE3:QUAT 632 -104.645 165.827 5.43395 -0.00689682 0.00370517 0.954481 0.298168 +VERTEX_SE3:QUAT 633 -108.03 168.269 5.39793 0.000348862 -0.000148323 0.955591 0.294695 +VERTEX_SE3:QUAT 634 -111.328 170.614 5.4084 -0.00655264 -0.000514883 0.957084 0.289735 +VERTEX_SE3:QUAT 635 -114.889 173.066 5.39294 -0.00942504 -0.00583375 0.956255 0.292325 +VERTEX_SE3:QUAT 636 -118.055 175.526 5.37657 -0.0157307 -0.00487751 0.933947 0.357031 +VERTEX_SE3:QUAT 637 -120.649 178.78 5.28 -0.018401 -0.00505862 0.864836 0.501692 +VERTEX_SE3:QUAT 638 -122.025 182.922 5.192 -0.016099 -0.00764314 0.757012 0.653158 +VERTEX_SE3:QUAT 639 -121.767 187.26 5.16793 -0.014082 -0.00803149 0.622314 0.7826 +VERTEX_SE3:QUAT 640 -120.218 191.03 5.16697 -0.0136684 -0.0074698 0.514609 0.857283 +VERTEX_SE3:QUAT 641 -117.717 194.657 5.17742 -0.00913907 -0.00602563 0.451336 0.892287 +VERTEX_SE3:QUAT 642 -115.229 197.825 5.20307 -0.0096291 -0.00818 0.453421 0.891207 +VERTEX_SE3:QUAT 643 -112.788 201.067 5.24387 -0.00916974 -0.00684406 0.463669 0.885935 +VERTEX_SE3:QUAT 644 -110.444 204.392 5.2812 -0.0148954 -0.000920376 0.472489 0.88121 +VERTEX_SE3:QUAT 645 -108.146 207.61 5.23996 -0.0128924 0.00027843 0.465881 0.884753 +VERTEX_SE3:QUAT 646 -105.754 210.872 5.20869 -0.012728 0.00112628 0.46012 0.887765 +VERTEX_SE3:QUAT 647 -103.26 214.192 5.17565 -0.0119545 -0.00058766 0.456846 0.889465 +VERTEX_SE3:QUAT 648 -100.809 217.441 5.15526 -0.0106959 -0.00180772 0.456483 0.889666 +VERTEX_SE3:QUAT 649 -98.2921 220.793 5.13885 -0.0124806 0.000810914 0.456654 0.889556 +VERTEX_SE3:QUAT 650 -95.7687 224.148 5.11071 -0.0124351 -0.00203697 0.457993 0.888866 +VERTEX_SE3:QUAT 651 -93.2573 227.511 5.09268 -0.0124063 -0.00136021 0.459565 0.888056 +VERTEX_SE3:QUAT 652 -90.7956 230.846 5.07962 -0.0121345 -0.00303707 0.461176 0.887221 +VERTEX_SE3:QUAT 653 -88.4402 234.067 5.07354 -0.0126667 -0.00289082 0.463366 0.886072 +VERTEX_SE3:QUAT 654 -86.049 237.358 5.0251 -0.0170159 0.0045975 0.465465 0.884891 +VERTEX_SE3:QUAT 655 -83.7134 240.593 4.95088 -0.0185064 0.00549184 0.465415 0.884882 +VERTEX_SE3:QUAT 656 -81.0638 244.187 4.87049 -0.0174528 0.00313067 0.455247 0.890189 +VERTEX_SE3:QUAT 657 -78.3773 247.563 4.80822 -0.0167336 0.00288516 0.428656 0.903308 +VERTEX_SE3:QUAT 658 -75.4576 250.582 4.77396 -0.0205641 0.0026304 0.348312 0.937149 +VERTEX_SE3:QUAT 659 -71.7335 252.705 4.7458 -0.0207225 0.00120421 0.16155 0.986646 +VERTEX_SE3:QUAT 660 -67.5833 253.06 4.75682 -0.0213141 -0.004196 -0.0693661 0.997355 +VERTEX_SE3:QUAT 661 -63.5115 251.573 4.84213 -0.0150897 -0.00355193 -0.235584 0.97173 +VERTEX_SE3:QUAT 662 -59.9395 249.337 4.87738 -0.00942889 0.00284468 -0.277178 0.960768 +VERTEX_SE3:QUAT 663 -56.6364 247.087 4.88037 -0.00741558 0.000327255 -0.284649 0.958603 +VERTEX_SE3:QUAT 664 -53.1126 244.622 4.92895 -0.00190318 0.00495054 -0.28904 0.957302 +VERTEX_SE3:QUAT 665 -49.5214 242.09 4.92758 -0.00424734 -0.00311287 -0.292928 0.95612 +VERTEX_SE3:QUAT 666 -46.0549 239.615 4.9887 -0.00775221 -0.00619191 -0.296189 0.955078 +VERTEX_SE3:QUAT 667 -42.5184 237.056 5.06489 -0.00998761 -0.0100957 -0.299124 0.954109 +VERTEX_SE3:QUAT 668 -38.8282 234.355 5.17977 -0.00728993 -0.0012454 -0.300539 0.953741 +VERTEX_SE3:QUAT 669 -35.2474 231.731 5.24857 -0.00647279 0.00686664 -0.301148 0.953531 +VERTEX_SE3:QUAT 670 -31.8858 229.27 5.25914 -0.00709604 0.00483201 -0.301024 0.953578 +VERTEX_SE3:QUAT 671 -28.5439 226.814 5.25539 -0.00739013 0.00131751 -0.300502 0.953752 +VERTEX_SE3:QUAT 672 -25.2602 224.401 5.26571 -0.00450747 0.00426261 -0.299791 0.953985 +VERTEX_SE3:QUAT 673 -22.0046 222.028 5.27521 -0.00536293 0.00427299 -0.298986 0.954233 +VERTEX_SE3:QUAT 674 -18.6241 219.593 5.30756 -0.00871829 -0.00195448 -0.294942 0.955473 +VERTEX_SE3:QUAT 675 -15.0701 217.017 5.38124 -0.0126225 0.000225433 -0.316381 0.948548 +VERTEX_SE3:QUAT 676 -11.841 214.161 5.3991 -0.00999689 0.00868614 -0.387318 0.921851 +VERTEX_SE3:QUAT 677 -9.41404 210.643 5.39256 -0.0115633 0.00578095 -0.543196 0.839506 +VERTEX_SE3:QUAT 678 -8.64547 206.634 5.42915 -0.0120139 0.000210811 -0.714472 0.699561 +VERTEX_SE3:QUAT 679 -9.62727 202.659 5.50655 -0.00817359 0.000198384 -0.838644 0.544618 +VERTEX_SE3:QUAT 680 -11.883 199.2 5.56797 -0.00453344 0.0028172 -0.911728 0.410759 +VERTEX_SE3:QUAT 681 -15.2643 196.707 5.60805 -0.00250997 0.000424836 -0.976246 0.216652 +VERTEX_SE3:QUAT 682 -19.4885 195.795 5.63032 -0.00767313 0.00381954 -0.999939 0.0069414 +VERTEX_SE3:QUAT 683 -23.6431 196.477 5.69428 0.00788079 -0.00528876 0.989783 0.142266 +VERTEX_SE3:QUAT 684 -27.3031 198.092 5.77393 -0.00941618 0.00347868 0.969597 0.2445 +VERTEX_SE3:QUAT 685 -30.816 200.474 5.7109 -0.00734622 0.00716666 0.951249 0.308253 +VERTEX_SE3:QUAT 686 -34.3402 203.299 5.62958 0.00314485 0.00857459 0.945617 0.325155 +VERTEX_SE3:QUAT 687 -37.4303 205.846 5.61437 0.00151202 0.00809105 0.944636 0.328018 +VERTEX_SE3:QUAT 688 -40.5234 208.417 5.63498 -0.00516837 0.00984655 0.944792 0.327481 +VERTEX_SE3:QUAT 689 -43.997 211.28 5.61111 -0.00374303 0.00858982 0.945904 0.324313 +VERTEX_SE3:QUAT 690 -47.5002 214.1 5.5759 -0.000159194 0.00455176 0.947105 0.320891 +VERTEX_SE3:QUAT 691 -50.973 216.868 5.52911 -0.00255128 0.00660376 0.948355 0.317131 +VERTEX_SE3:QUAT 692 -54.4715 219.621 5.4688 -0.0063889 0.0105389 0.949713 0.312878 +VERTEX_SE3:QUAT 693 -57.9624 222.31 5.41288 -0.0108324 0.014056 0.951134 0.308268 +VERTEX_SE3:QUAT 694 -61.4827 224.976 5.32513 -0.00483649 0.0122877 0.952457 0.304386 +VERTEX_SE3:QUAT 695 -64.8685 227.479 5.29733 -0.000869177 0.00927888 0.95435 0.298546 +VERTEX_SE3:QUAT 696 -68.5661 230.053 5.26252 0.00474229 0.00727142 0.9612 0.275716 +VERTEX_SE3:QUAT 697 -72.1626 232.254 5.2811 0.00131306 0.0051945 0.972072 0.23462 +VERTEX_SE3:QUAT 698 -75.9225 233.981 5.2799 -0.010512 0.0119741 0.987095 0.159338 +VERTEX_SE3:QUAT 699 -79.8301 235.038 5.20727 -0.00445485 0.0150951 0.997526 0.0685199 +VERTEX_SE3:QUAT 700 -84.2817 235.245 5.18804 0.000467161 -0.0152969 -0.997814 0.0642923 +VERTEX_SE3:QUAT 701 -88.538 234.155 5.19286 0.0105608 -0.00603988 -0.978507 0.205855 +VERTEX_SE3:QUAT 702 -92.1843 232.095 5.14449 0.00913831 -0.00707139 -0.947562 0.319363 +VERTEX_SE3:QUAT 703 -95.4926 229.263 5.12407 0.00475855 -0.00665785 -0.923817 0.382747 +VERTEX_SE3:QUAT 704 -98.5214 226.081 5.12582 0.000589677 -0.00291243 -0.908489 0.417899 +VERTEX_SE3:QUAT 705 -101.162 223.007 5.15051 0.000203015 -0.00631713 -0.899474 0.436929 +VERTEX_SE3:QUAT 706 -103.983 219.423 5.17048 0.00171301 -0.00136158 -0.890832 0.454329 +VERTEX_SE3:QUAT 707 -106.548 215.889 5.18558 -0.000107622 -0.00026461 -0.882358 0.470579 +VERTEX_SE3:QUAT 708 -109.029 212.279 5.21137 0.000131585 -0.00270556 -0.876944 0.480585 +VERTEX_SE3:QUAT 709 -111.309 208.807 5.24314 -0.00472347 -0.0053122 -0.871704 0.489981 +VERTEX_SE3:QUAT 710 -113.55 205.2 5.29622 0.010529 0.00108519 -0.866031 0.499877 +VERTEX_SE3:QUAT 711 -115.673 201.518 5.23309 0.00758295 -0.00143972 -0.856059 0.516821 +VERTEX_SE3:QUAT 712 -117.625 197.792 5.20391 0.00751528 -0.00462183 -0.844266 0.535852 +VERTEX_SE3:QUAT 713 -119.411 193.987 5.18875 0.00626604 -0.00571128 -0.830184 0.557425 +VERTEX_SE3:QUAT 714 -120.925 190.072 5.18834 0.00520692 -0.00707578 -0.797833 0.602814 +VERTEX_SE3:QUAT 715 -121.728 186.021 5.20242 0.00915403 -0.00707494 -0.716743 0.697242 +VERTEX_SE3:QUAT 716 -121.278 181.892 5.21845 0.00287807 -0.0127699 -0.595334 0.803371 +VERTEX_SE3:QUAT 717 -119.569 178.068 5.30459 3.57043e-05 -0.0148418 -0.470827 0.882101 +VERTEX_SE3:QUAT 718 -116.783 174.721 5.39386 0.00502385 0.00138061 -0.370683 0.928745 +VERTEX_SE3:QUAT 719 -113.711 172.062 5.40423 0.00032265 0.00362261 -0.313251 0.949663 +VERTEX_SE3:QUAT 720 -110.262 169.602 5.40823 -0.00467379 0.00196528 -0.284671 0.958612 +VERTEX_SE3:QUAT 721 -106.712 167.25 5.40241 -0.00646404 0.00209859 -0.276299 0.961048 +VERTEX_SE3:QUAT 722 -103.115 164.924 5.43554 -0.00993513 -0.00596356 -0.270903 0.962537 +VERTEX_SE3:QUAT 723 -99.5538 162.657 5.53293 -0.00577374 -0.00193727 -0.266399 0.963844 +VERTEX_SE3:QUAT 724 -96.0592 160.471 5.60571 -0.00342051 -0.00400836 -0.261933 0.965072 +VERTEX_SE3:QUAT 725 -92.2804 158.175 5.68431 -0.00284439 -0.00778545 -0.257382 0.966274 +VERTEX_SE3:QUAT 726 -88.414 155.886 5.71895 -0.000279871 -0.000850496 -0.25224 0.967664 +VERTEX_SE3:QUAT 727 -85.0205 153.873 5.74328 0.000194026 0.00679443 -0.257442 0.96627 +VERTEX_SE3:QUAT 728 -81.5429 151.764 5.73799 -0.00139669 0.00823651 -0.264031 0.964478 +VERTEX_SE3:QUAT 729 -78.0763 149.591 5.70494 -0.00465292 0.0019447 -0.270383 0.96274 +VERTEX_SE3:QUAT 730 -74.7264 147.427 5.72541 -0.00559543 -0.00878495 -0.273801 0.96173 +VERTEX_SE3:QUAT 731 -71.3772 145.24 5.81946 -0.00323321 -0.00310665 -0.274662 0.96153 +VERTEX_SE3:QUAT 732 -67.7842 142.967 5.91231 0.00365489 0.010216 -0.250314 0.968104 +VERTEX_SE3:QUAT 733 -64.0107 141.075 5.83816 0.00613658 0.00408491 -0.16727 0.985884 +VERTEX_SE3:QUAT 734 -59.8307 140.144 5.82247 0.00475118 -0.0022064 -0.0127504 0.999905 +VERTEX_SE3:QUAT 735 -55.698 140.598 5.8372 0.00605212 -0.0023118 0.158028 0.987413 +VERTEX_SE3:QUAT 736 -52.015 142.369 5.87406 0.00367867 0.00347891 0.314953 0.949094 +VERTEX_SE3:QUAT 737 -48.9585 145.243 5.8949 0.000691168 0.000413949 0.438414 0.898773 +VERTEX_SE3:QUAT 738 -46.6526 148.859 5.92512 0.00231137 -0.00086316 0.537088 0.843523 +VERTEX_SE3:QUAT 739 -45.1282 152.61 5.96686 -0.000696233 -0.0083648 0.579496 0.814932 +VERTEX_SE3:QUAT 740 -43.6551 156.469 6.01218 -0.00652719 0.00603679 0.56437 0.825474 +VERTEX_SE3:QUAT 741 -41.9829 160.164 5.96037 -0.00695707 0.00140049 0.521139 0.853442 +VERTEX_SE3:QUAT 742 -39.72 163.769 5.93595 -0.00749762 0.00163567 0.465549 0.884989 +VERTEX_SE3:QUAT 743 -37.1532 167.093 5.90771 -0.00632402 0.00115714 0.433689 0.90104 +VERTEX_SE3:QUAT 744 -34.4105 170.23 5.89666 -0.00681013 0.0020017 0.416319 0.909191 +VERTEX_SE3:QUAT 745 -31.5485 173.354 5.88055 -0.0040378 0.00305997 0.409911 0.912112 +VERTEX_SE3:QUAT 746 -28.66 176.43 5.86433 -0.000638599 0.00248626 0.407714 0.913106 +VERTEX_SE3:QUAT 747 -25.9576 179.331 5.86141 0.00197769 0.00451478 0.422527 0.906337 +VERTEX_SE3:QUAT 748 -23.3999 182.585 5.8546 0.00235938 -0.00111421 0.492423 0.870352 +VERTEX_SE3:QUAT 749 -21.726 186.568 5.8789 -0.00397053 0.0119766 0.647921 0.761603 +VERTEX_SE3:QUAT 750 -21.741 190.695 5.79461 0.000858912 0.0122592 0.783519 0.621246 +VERTEX_SE3:QUAT 751 -23.4067 194.672 5.75982 0.00428241 0.00994004 0.881472 0.472112 +VERTEX_SE3:QUAT 752 -26.3213 198.125 5.79067 -0.00565681 0.00826294 0.929069 0.369771 +VERTEX_SE3:QUAT 753 -29.5672 201.055 5.71609 -0.00646692 0.00782431 0.940078 0.340809 +VERTEX_SE3:QUAT 754 -32.6666 203.698 5.63189 -0.00140731 0.00773934 0.943932 0.330046 +VERTEX_SE3:QUAT 755 -35.9765 206.413 5.60423 -0.00441583 0.00837588 0.946938 0.321275 +VERTEX_SE3:QUAT 756 -39.3378 209.104 5.60087 -0.00578844 0.00879878 0.948319 0.317144 +VERTEX_SE3:QUAT 757 -42.7058 211.738 5.56823 -0.00205139 0.00495502 0.949335 0.314221 +VERTEX_SE3:QUAT 758 -46.0784 214.35 5.53107 0.00149753 0.00422869 0.950216 0.311558 +VERTEX_SE3:QUAT 759 -49.4055 216.888 5.52398 -0.0115759 0.00713864 0.950857 0.30933 +VERTEX_SE3:QUAT 760 -52.627 219.382 5.4538 -0.0157826 0.0114151 0.950106 0.311318 +VERTEX_SE3:QUAT 761 -56.0603 222.048 5.3459 -0.0100201 0.0112466 0.948605 0.316105 +VERTEX_SE3:QUAT 762 -59.4086 224.721 5.24377 -0.00452355 0.00998748 0.946317 0.323055 +VERTEX_SE3:QUAT 763 -62.7138 227.449 5.17367 4.798e-06 0.00966829 0.943949 0.329949 +VERTEX_SE3:QUAT 764 -65.9937 230.206 5.15929 -0.00589677 0.00895663 0.942169 0.334968 +VERTEX_SE3:QUAT 765 -69.1252 232.876 5.13624 -0.00315008 0.0035688 0.94163 0.336617 +VERTEX_SE3:QUAT 766 -72.1984 235.486 5.13042 -0.00640198 0.00668314 0.948188 0.317576 +VERTEX_SE3:QUAT 767 -75.5933 237.777 5.05184 -0.0132434 0.0128403 0.97653 0.214589 +VERTEX_SE3:QUAT 768 -79.7226 238.966 4.94968 -0.00589271 0.0153126 0.999562 0.0246106 +VERTEX_SE3:QUAT 769 -83.8454 238.527 4.93395 0.00117078 -0.0149543 -0.98563 0.168253 +VERTEX_SE3:QUAT 770 -87.5121 236.436 4.97654 0.00472139 -0.0107593 -0.925656 0.378185 +VERTEX_SE3:QUAT 771 -89.9347 232.892 4.98853 0.00667291 -0.0108017 -0.812033 0.583474 +VERTEX_SE3:QUAT 772 -90.3937 228.642 5.0204 0.0040048 -0.0104177 -0.644703 0.764352 +VERTEX_SE3:QUAT 773 -88.8178 224.66 5.09672 -0.0012871 -0.0133349 -0.462852 0.886334 +VERTEX_SE3:QUAT 774 -85.9107 221.486 5.24928 -0.00264009 0.00693808 -0.352008 0.935968 +VERTEX_SE3:QUAT 775 -82.6391 218.757 5.17916 -0.00104583 0.0182495 -0.319468 0.947421 +VERTEX_SE3:QUAT 776 -79.3184 216.179 5.02966 -0.000884977 0.0232961 -0.31101 0.950121 +VERTEX_SE3:QUAT 777 -75.8899 213.563 4.87179 0.00211301 0.0300061 -0.307036 0.951223 +VERTEX_SE3:QUAT 778 -72.4364 210.958 4.68318 0.000555559 0.0267507 -0.306485 0.951499 +VERTEX_SE3:QUAT 779 -68.9556 208.325 4.5113 -0.00233438 0.0227728 -0.309173 0.95073 +VERTEX_SE3:QUAT 780 -65.5228 205.707 4.33915 -0.0024094 0.0215837 -0.309181 0.950755 +VERTEX_SE3:QUAT 781 -62.0718 203.081 4.17514 0.000566061 0.0284333 -0.308291 0.950867 +VERTEX_SE3:QUAT 782 -58.6115 200.478 4.00161 -0.00161699 0.0321695 -0.306129 0.951445 +VERTEX_SE3:QUAT 783 -55.2617 197.955 3.7982 0.00197795 0.0290714 -0.30413 0.952185 +VERTEX_SE3:QUAT 784 -51.9574 195.515 3.58518 0.00115472 0.0230763 -0.301181 0.953287 +VERTEX_SE3:QUAT 785 -48.46 192.971 3.39111 0.000895406 0.0282202 -0.297576 0.954281 +VERTEX_SE3:QUAT 786 -45.089 190.566 3.18513 0.00170236 0.0291552 -0.291995 0.955974 +VERTEX_SE3:QUAT 787 -41.6982 188.199 3.01063 0.00653993 0.0296386 -0.289587 0.95667 +VERTEX_SE3:QUAT 788 -38.1357 185.671 2.76533 0.00433836 0.027114 -0.300746 0.953309 +VERTEX_SE3:QUAT 789 -35.009 183.043 2.61651 -0.00616043 0.00773241 -0.390732 0.920452 +VERTEX_SE3:QUAT 790 -32.6586 179.624 2.58762 -0.00683893 0.00911019 -0.545563 0.837992 +VERTEX_SE3:QUAT 791 -31.873 175.471 2.57218 -0.0083749 0.0064992 -0.724051 0.689665 +VERTEX_SE3:QUAT 792 -33.1665 171.465 2.6023 -0.0035308 0.0106161 -0.879113 0.476482 +VERTEX_SE3:QUAT 793 -36.2143 168.796 2.61494 -0.00100996 0.00665108 -0.973932 0.22674 +VERTEX_SE3:QUAT 794 -40.4263 168.055 2.63207 0.00429632 -0.00624008 0.998831 0.0477345 +VERTEX_SE3:QUAT 795 -44.2069 169.291 2.67045 0.00737245 -0.00675555 0.971671 0.236125 +VERTEX_SE3:QUAT 796 -47.6097 171.57 2.72621 -0.0370838 0.0104487 0.95182 0.304227 +VERTEX_SE3:QUAT 797 -50.8401 174.011 2.45545 -0.0305447 0.00670763 0.950657 0.308663 +VERTEX_SE3:QUAT 798 -54.3292 176.652 2.20996 -0.0297533 0.00646029 0.951803 0.305195 +VERTEX_SE3:QUAT 799 -57.8108 179.223 1.94592 -0.0281062 0.00787997 0.953369 0.300393 +VERTEX_SE3:QUAT 800 -61.2807 181.755 1.71286 -0.032235 0.00922636 0.953304 0.300145 +VERTEX_SE3:QUAT 801 -64.7405 184.281 1.4757 -0.0348335 0.00928985 0.953325 0.299787 +VERTEX_SE3:QUAT 802 -68.1833 186.793 1.22367 -0.0320776 0.00790964 0.953596 0.29927 +VERTEX_SE3:QUAT 803 -71.5935 189.278 0.958195 -0.029485 0.00793868 0.953961 0.298373 +VERTEX_SE3:QUAT 804 -75.1026 191.826 0.701837 -0.0344842 0.0109088 0.954203 0.296966 +VERTEX_SE3:QUAT 805 -78.5692 194.311 0.425655 -0.034067 0.00945498 0.954831 0.29504 +VERTEX_SE3:QUAT 806 -82.0081 196.758 0.172834 -0.037994 0.00943879 0.955286 0.293081 +VERTEX_SE3:QUAT 807 -85.4599 199.2 -0.134119 -0.0312147 0.0098717 0.956171 0.290974 +VERTEX_SE3:QUAT 808 -88.8616 201.567 -0.406285 -0.0308813 0.00949879 0.956806 0.288925 +VERTEX_SE3:QUAT 809 -92.2521 203.952 -0.671264 -0.0372088 0.0109866 0.952919 0.300733 +VERTEX_SE3:QUAT 810 -95.4383 206.473 -0.953147 -0.0237293 0.00260781 0.933319 0.358254 +VERTEX_SE3:QUAT 811 -98.0854 209.665 -1.11809 -0.0201849 0.000684143 0.868615 0.495076 +VERTEX_SE3:QUAT 812 -99.3941 213.776 -1.24205 -0.0157747 -0.00358883 0.732748 0.680308 +VERTEX_SE3:QUAT 813 -98.677 217.853 -1.29084 -0.017926 -0.00470509 0.541761 0.840328 +VERTEX_SE3:QUAT 814 -96.0096 220.981 -1.30734 -0.0185903 -0.00257059 0.28841 0.957323 +VERTEX_SE3:QUAT 815 -92.0346 222.204 -1.28811 -0.0189787 -0.00765783 0.0149818 0.999678 +VERTEX_SE3:QUAT 816 -88.0507 221.426 -1.18406 -0.0152048 -0.00961956 -0.185931 0.982398 +VERTEX_SE3:QUAT 817 -84.2858 219.218 -1.12769 -0.00129683 0.025125 -0.299255 0.953841 +VERTEX_SE3:QUAT 818 -80.7931 216.527 -1.29929 0.000233879 0.0252763 -0.317218 0.948016 +VERTEX_SE3:QUAT 819 -77.535 213.967 -1.45857 0.00146025 0.022294 -0.312095 0.949788 +VERTEX_SE3:QUAT 820 -74.0523 211.327 -1.61395 -0.00010719 0.0233387 -0.305632 0.951864 +VERTEX_SE3:QUAT 821 -70.8306 208.952 -1.76243 -0.00154343 0.0271971 -0.300283 0.953461 +VERTEX_SE3:QUAT 822 -67.5294 206.539 -1.95205 0.00157937 0.025048 -0.297052 0.954531 +VERTEX_SE3:QUAT 823 -64.1009 204.083 -2.13708 0.000695368 0.0227454 -0.295195 0.955166 +VERTEX_SE3:QUAT 824 -60.6305 201.61 -2.30825 0.00102398 0.0250304 -0.292927 0.955806 +VERTEX_SE3:QUAT 825 -57.0268 199.052 -2.49276 0.00385102 0.0284337 -0.293179 0.955627 +VERTEX_SE3:QUAT 826 -53.5972 196.614 -2.70704 0.00361878 0.0274782 -0.294519 0.955243 +VERTEX_SE3:QUAT 827 -50.2725 194.224 -2.89214 0.00335609 0.0274162 -0.296213 0.954723 +VERTEX_SE3:QUAT 828 -46.8296 191.728 -3.09843 0.00369561 0.0293018 -0.299264 0.953713 +VERTEX_SE3:QUAT 829 -43.5578 189.319 -3.2871 0.00264456 0.0314051 -0.301901 0.952818 +VERTEX_SE3:QUAT 830 -40.3189 186.924 -3.50922 0.00246876 0.0382117 -0.303082 0.952195 +VERTEX_SE3:QUAT 831 -37.038 184.468 -3.78623 0.00534923 0.0309394 -0.303884 0.952191 +VERTEX_SE3:QUAT 832 -33.78 182.041 -4.02041 0.00514736 0.0210844 -0.302285 0.952971 +VERTEX_SE3:QUAT 833 -30.372 179.542 -4.16427 0.00108148 0.00738527 -0.29686 0.954892 +VERTEX_SE3:QUAT 834 -27.0181 177.148 -4.19141 -0.00369791 0.00338594 -0.292617 0.956217 +VERTEX_SE3:QUAT 835 -23.6338 174.781 -4.1794 -0.0105248 -0.0113527 -0.289934 0.956922 +VERTEX_SE3:QUAT 836 -20.3097 172.507 -4.02944 -0.00838297 0.0158607 -0.287976 0.957469 +VERTEX_SE3:QUAT 837 -16.8855 169.981 -4.1326 0.00171761 0.0163911 -0.370402 0.928725 +VERTEX_SE3:QUAT 838 -14.9745 166.388 -4.17145 -0.00470188 -0.0162913 -0.66864 0.743393 +VERTEX_SE3:QUAT 839 -15.8825 162.242 -4.09044 -0.00299619 -0.0170548 -0.848408 0.52906 +VERTEX_SE3:QUAT 840 -18.2841 158.87 -4.02674 0.00166926 -0.0166607 -0.90153 0.432392 +VERTEX_SE3:QUAT 841 -21.0858 155.582 -3.9855 0.00264054 -0.016678 -0.90139 0.432678 +VERTEX_SE3:QUAT 842 -23.7636 152.375 -3.94062 0.00374586 -0.0163259 -0.897762 0.440163 +VERTEX_SE3:QUAT 843 -26.6151 148.781 -3.90475 0.00298852 -0.0180333 -0.891661 0.452336 +VERTEX_SE3:QUAT 844 -29.3778 145.056 -3.84724 0.00129225 -0.0149576 -0.885063 0.465228 +VERTEX_SE3:QUAT 845 -31.7184 141.773 -3.79649 0.000636107 -0.0165343 -0.87918 0.476202 +VERTEX_SE3:QUAT 846 -34.1488 138.163 -3.73248 0.00401541 -0.0182893 -0.873562 0.486352 +VERTEX_SE3:QUAT 847 -36.3557 134.77 -3.68149 0.00266703 -0.0201124 -0.871862 0.489331 +VERTEX_SE3:QUAT 848 -38.5824 131.35 -3.59647 -0.00353015 -0.0253248 -0.872112 0.488638 +VERTEX_SE3:QUAT 849 -41.0217 127.562 -3.44141 -0.0103396 -0.0190531 -0.874979 0.483676 +VERTEX_SE3:QUAT 850 -43.4801 123.936 -3.27653 -0.0171361 -0.0171172 -0.881056 0.472391 +VERTEX_SE3:QUAT 851 -45.806 120.587 -3.06754 -0.013602 -0.0112249 -0.880043 0.474567 +VERTEX_SE3:QUAT 852 -48.0856 117.198 -2.8881 -0.0165141 -0.00809957 -0.878705 0.477011 +VERTEX_SE3:QUAT 853 -50.6122 113.71 -2.71533 -0.0120985 -0.00641439 -0.901932 0.431662 +VERTEX_SE3:QUAT 854 -53.5409 110.885 -2.58442 -0.0109392 -0.00316512 -0.956507 0.291486 +VERTEX_SE3:QUAT 855 -57.57 109.696 -2.51029 0.0196562 0.00554371 0.999558 0.0215935 +VERTEX_SE3:QUAT 856 -61.6117 111.218 -2.37014 0.0154907 0.0134797 0.961001 0.275782 +VERTEX_SE3:QUAT 857 -64.9011 113.79 -2.29442 0.0131513 0.0201314 0.943136 0.331536 +VERTEX_SE3:QUAT 858 -68.0878 116.466 -2.24173 0.0134198 0.0205473 0.944961 0.326261 +VERTEX_SE3:QUAT 859 -71.4678 119.158 -2.18687 0.013325 0.0205746 0.949037 0.314211 +VERTEX_SE3:QUAT 860 -74.6907 121.636 -2.13697 0.00753031 0.0209173 0.951251 0.307615 +VERTEX_SE3:QUAT 861 -78.1078 124.217 -2.12688 0.00753108 0.0226485 0.952254 0.304372 +VERTEX_SE3:QUAT 862 -81.544 126.777 -2.11842 0.00765727 0.0228318 0.952899 0.302329 +VERTEX_SE3:QUAT 863 -85.0145 129.342 -2.10058 0.00509473 0.0233349 0.953153 0.301545 +VERTEX_SE3:QUAT 864 -88.6137 131.988 -2.11624 0.00488451 0.0209391 0.953152 0.301727 +VERTEX_SE3:QUAT 865 -92.2478 134.669 -2.12151 0.00416324 0.0187651 0.953303 0.301404 +VERTEX_SE3:QUAT 866 -96.005 137.417 -2.12711 0.00227864 0.017545 0.953155 0.301963 +VERTEX_SE3:QUAT 867 -99.2333 139.794 -2.14375 0.00184447 0.0153643 0.953009 0.302546 +VERTEX_SE3:QUAT 868 -102.527 142.215 -2.14984 -0.00187265 0.0131678 0.952975 0.302755 +VERTEX_SE3:QUAT 869 -105.768 144.616 -2.18359 -0.00167782 0.0125363 0.95284 0.303208 +VERTEX_SE3:QUAT 870 -109.103 147.1 -2.21589 -0.00267824 0.014334 0.952643 0.30374 +VERTEX_SE3:QUAT 871 -112.34 149.525 -2.264 -0.00249502 0.0141226 0.952478 0.304271 +VERTEX_SE3:QUAT 872 -115.719 152.05 -2.29989 -0.00403606 0.0151538 0.952687 0.303548 +VERTEX_SE3:QUAT 873 -118.996 154.474 -2.34809 -0.00461586 0.0143334 0.953042 0.302465 +VERTEX_SE3:QUAT 874 -122.282 156.931 -2.39977 -0.00401872 0.016368 0.952316 0.304647 +VERTEX_SE3:QUAT 875 -125.856 159.629 -2.46148 -0.00716972 0.0181008 0.950804 0.30918 +VERTEX_SE3:QUAT 876 -129.287 162.257 -2.5462 -0.00739561 0.0163064 0.94942 0.313497 +VERTEX_SE3:QUAT 877 -132.535 164.811 -2.63097 -0.00870463 0.0152207 0.9478 0.318382 +VERTEX_SE3:QUAT 878 -136.009 167.501 -2.72442 -0.00978272 0.0147475 0.956851 0.290039 +VERTEX_SE3:QUAT 879 -139.618 169.576 -2.80001 -0.00507702 0.0139699 0.983055 0.182705 +VERTEX_SE3:QUAT 880 -143.782 170.442 -2.83645 0.00107648 -0.0146514 -0.999666 0.0212662 +VERTEX_SE3:QUAT 881 -147.822 169.48 -2.83669 0.0019894 -0.0124739 -0.970004 0.24276 +VERTEX_SE3:QUAT 882 -151.184 166.725 -2.80852 -0.00074493 -0.0128998 -0.901616 0.432345 +VERTEX_SE3:QUAT 883 -153.617 163.192 -2.75227 -0.00311177 -0.00838859 -0.86862 0.495398 +VERTEX_SE3:QUAT 884 -155.869 159.475 -2.68879 -0.00541674 -0.00843983 -0.865014 0.501648 +VERTEX_SE3:QUAT 885 -157.949 156.027 -2.60596 -0.00645999 -0.00527613 -0.873563 0.48664 +VERTEX_SE3:QUAT 886 -160.366 152.706 -2.52441 -0.00255557 -0.00711589 -0.901869 0.431943 +VERTEX_SE3:QUAT 887 -163.275 149.768 -2.47149 -0.00173734 -0.00482508 -0.944336 0.328944 +VERTEX_SE3:QUAT 888 -166.959 147.965 -2.43267 0.00588053 -0.00620011 -0.993868 0.110243 +VERTEX_SE3:QUAT 889 -171.015 147.973 -2.47637 -0.001527 -0.00331016 0.993127 0.116983 +VERTEX_SE3:QUAT 890 -174.713 149.689 -2.47545 -0.00368255 0.00267127 0.957325 0.288978 +VERTEX_SE3:QUAT 891 -177.861 152.386 -2.54732 -0.0226134 0.016784 0.907958 0.418114 +VERTEX_SE3:QUAT 892 -179.452 156.151 -2.71009 0.00388314 0.000442208 0.721062 0.692859 +VERTEX_SE3:QUAT 893 -178.246 160.428 -2.74501 0.000591814 0.00626782 0.509578 0.860401 +VERTEX_SE3:QUAT 894 -175.679 163.963 -2.81646 -0.000899478 0.0089947 0.443565 0.896196 +VERTEX_SE3:QUAT 895 -172.826 167.487 -2.90307 -0.00282502 0.00729078 0.440904 0.89752 +VERTEX_SE3:QUAT 896 -170.104 170.871 -2.9656 -0.00279433 0.00793848 0.444084 0.895946 +VERTEX_SE3:QUAT 897 -167.263 174.477 -3.04182 -0.00223576 0.00956115 0.446596 0.894682 +VERTEX_SE3:QUAT 898 -164.687 177.738 -3.10836 -0.00372614 0.00873462 0.44609 0.894938 +VERTEX_SE3:QUAT 899 -161.663 181.558 -3.19288 -0.0021784 0.0119593 0.445274 0.895312 +VERTEX_SE3:QUAT 900 -159.067 184.826 -3.27975 -0.000512841 0.0107976 0.444758 0.895586 +VERTEX_SE3:QUAT 901 -156.398 188.179 -3.36125 -0.00232353 0.0105627 0.443741 0.89609 +VERTEX_SE3:QUAT 902 -153.717 191.537 -3.4475 -0.000951226 0.0117218 0.443787 0.896055 +VERTEX_SE3:QUAT 903 -151.011 194.901 -3.52443 -0.00257622 0.0132315 0.443006 0.896418 +VERTEX_SE3:QUAT 904 -148.365 198.194 -3.61944 -0.00202736 0.0129254 0.44255 0.896648 +VERTEX_SE3:QUAT 905 -145.611 201.63 -3.71794 -0.000501083 0.0159126 0.448007 0.893888 +VERTEX_SE3:QUAT 906 -143.141 204.953 -3.80706 -0.00380682 0.0119757 0.464734 0.885361 +VERTEX_SE3:QUAT 907 -140.801 208.259 -3.88855 -0.00344092 0.0141967 0.474075 0.880363 +VERTEX_SE3:QUAT 908 -138.292 211.944 -3.99427 -0.00348363 0.0125931 0.478452 0.878016 +VERTEX_SE3:QUAT 909 -135.9 215.461 -4.08011 -0.00161724 0.0137665 0.475791 0.879449 +VERTEX_SE3:QUAT 910 -133.46 218.917 -4.16965 -0.000584704 0.0157235 0.46234 0.886563 +VERTEX_SE3:QUAT 911 -130.913 222.18 -4.26908 -0.0049217 0.0164166 0.420571 0.907098 +VERTEX_SE3:QUAT 912 -127.732 224.945 -4.40734 -0.00371379 0.0198537 0.242015 0.970062 +VERTEX_SE3:QUAT 913 -123.679 225.505 -4.42466 -0.0261802 -0.00965953 -0.138028 0.990035 +VERTEX_SE3:QUAT 914 -120.152 223.575 -4.30179 -0.0199355 -0.00435192 -0.308876 0.950883 +VERTEX_SE3:QUAT 915 -116.756 220.825 -4.21556 -0.0155734 -0.00418283 -0.324294 0.945819 +VERTEX_SE3:QUAT 916 -113.491 218.232 -4.13877 -0.0155849 -0.00421174 -0.314668 0.949064 +VERTEX_SE3:QUAT 917 -110.298 215.756 -4.05557 -0.0116073 -1.3767e-05 -0.31373 0.949441 +VERTEX_SE3:QUAT 918 -107.136 213.301 -4.04627 -0.0108929 0.00608505 -0.313168 0.949616 +VERTEX_SE3:QUAT 919 -103.943 210.831 -4.05345 -0.010625 0.00537601 -0.311947 0.950025 +VERTEX_SE3:QUAT 920 -100.725 208.376 -4.05846 -0.0184199 -0.0207077 -0.310478 0.950176 +VERTEX_SE3:QUAT 921 -97.3373 205.796 -3.8517 -0.0174966 -0.0205067 -0.309245 0.9506 +VERTEX_SE3:QUAT 922 -93.9448 203.207 -3.63497 -0.0200514 -0.0224628 -0.30819 0.950848 +VERTEX_SE3:QUAT 923 -90.4759 200.571 -3.43202 -0.0141014 -0.019059 -0.30739 0.951288 +VERTEX_SE3:QUAT 924 -87.0607 197.992 -3.23837 -0.0131809 -0.0180702 -0.306372 0.951649 +VERTEX_SE3:QUAT 925 -83.5951 195.4 -3.06013 -0.0131993 -0.017411 -0.30627 0.951694 +VERTEX_SE3:QUAT 926 -80.1308 192.8 -2.87871 -0.0139405 -0.0176081 -0.305569 0.951905 +VERTEX_SE3:QUAT 927 -76.5636 190.169 -2.68944 -0.0140603 -0.0153555 -0.301131 0.953355 +VERTEX_SE3:QUAT 928 -73.0217 187.569 -2.5139 -0.0131613 -0.0133262 -0.299639 0.953869 +VERTEX_SE3:QUAT 929 -69.4501 184.966 -2.35904 -0.0160078 -0.0146323 -0.299978 0.9537 +VERTEX_SE3:QUAT 930 -65.9488 182.398 -2.19813 -0.01387 -0.0130979 -0.301197 0.953371 +VERTEX_SE3:QUAT 931 -62.4908 179.846 -2.04844 -0.013148 -0.0115587 -0.302753 0.952908 +VERTEX_SE3:QUAT 932 -59.1297 177.357 -1.90024 -0.0125761 -0.00994079 -0.303685 0.952638 +VERTEX_SE3:QUAT 933 -55.8908 174.956 -1.76341 -0.0128354 -0.00760049 -0.303874 0.952596 +VERTEX_SE3:QUAT 934 -52.4472 172.385 -1.63856 -0.0110422 -0.00926482 -0.304501 0.952403 +VERTEX_SE3:QUAT 935 -49.0577 169.836 -1.47833 -0.00746358 0.00501785 -0.311999 0.95004 +VERTEX_SE3:QUAT 936 -45.8404 167.259 -1.52619 -0.00459234 0.0182027 -0.316673 0.948349 +VERTEX_SE3:QUAT 937 -42.3344 165.216 -1.6604 0.000496668 0.0147007 -0.104741 0.994391 +VERTEX_SE3:QUAT 938 -38.0903 165.451 -1.78641 0.00426588 0.0119933 0.188387 0.982012 +VERTEX_SE3:QUAT 939 -34.5292 167.493 -1.87569 0.0108382 0.00944152 0.353126 0.935465 +VERTEX_SE3:QUAT 940 -31.6845 170.787 -1.89571 0.00931761 0.0152654 0.509852 0.860076 +VERTEX_SE3:QUAT 941 -30.2925 174.576 -1.92644 0.0105457 0.010032 0.656759 0.75396 +VERTEX_SE3:QUAT 942 -30.4493 178.921 -1.90968 0.0191248 0.0068847 0.805145 0.592729 +VERTEX_SE3:QUAT 943 -32.5154 182.751 -1.80762 0.018094 6.96615e-05 0.905839 0.423235 +VERTEX_SE3:QUAT 944 -35.4467 185.748 -1.68126 0.0300756 -0.00471896 0.940519 0.338373 +VERTEX_SE3:QUAT 945 -38.954 188.545 -1.39809 0.0323393 -0.00756629 0.948634 0.314627 +VERTEX_SE3:QUAT 946 -42.1467 191.013 -1.14561 0.0406177 -0.0094326 0.949889 0.309794 +VERTEX_SE3:QUAT 947 -45.4785 193.536 -0.838171 0.0339446 -0.00867128 0.950984 0.30725 +VERTEX_SE3:QUAT 948 -48.9027 196.1 -0.521904 0.0294841 -0.00572145 0.951654 0.305701 +VERTEX_SE3:QUAT 949 -52.3971 198.708 -0.226317 0.0294978 -0.0059602 0.95199 0.304646 +VERTEX_SE3:QUAT 950 -55.7889 201.222 0.0399733 0.0348109 -0.00713592 0.952169 0.303498 +VERTEX_SE3:QUAT 951 -59.3277 203.842 0.3048 0.036115 -0.0083621 0.952506 0.302256 +VERTEX_SE3:QUAT 952 -62.5246 206.195 0.574878 0.0287475 -0.00718535 0.953062 0.301322 +VERTEX_SE3:QUAT 953 -65.9637 208.728 0.85217 0.0257037 -0.0054653 0.953517 0.30019 +VERTEX_SE3:QUAT 954 -69.54 211.336 1.09999 0.0277869 -0.00789771 0.953725 0.299289 +VERTEX_SE3:QUAT 955 -73.0364 213.88 1.34934 0.0318454 -0.00735078 0.951958 0.30448 +VERTEX_SE3:QUAT 956 -76.5146 216.555 1.62029 0.0307399 -0.00681641 0.948961 0.313819 +VERTEX_SE3:QUAT 957 -79.8406 219.16 1.90178 0.0278602 -0.00541011 0.948122 0.316638 +VERTEX_SE3:QUAT 958 -83.1563 221.765 2.18189 -0.00287604 0.00609783 0.950749 0.309889 +VERTEX_SE3:QUAT 959 -86.7112 224.217 2.14574 -0.00285021 0.0080569 0.972797 0.231502 +VERTEX_SE3:QUAT 960 -90.6518 225.571 2.12153 0.00679684 0.00571686 0.998351 0.0567193 +VERTEX_SE3:QUAT 961 -95.0661 225.262 2.19735 -0.00211241 -0.00728424 -0.985163 0.171453 +VERTEX_SE3:QUAT 962 -98.6518 223.082 2.24577 -0.00732435 -0.00471368 -0.920146 0.391479 +VERTEX_SE3:QUAT 963 -101.1 219.651 2.30629 -0.00232968 -0.00379627 -0.831055 0.556172 +VERTEX_SE3:QUAT 964 -102.016 215.526 2.35147 -0.00634855 0.00172532 -0.699221 0.714875 +VERTEX_SE3:QUAT 965 -101.177 211.358 2.37885 -0.00893004 -0.000398941 -0.538004 0.842895 +VERTEX_SE3:QUAT 966 -98.9314 207.789 2.4206 -0.00782113 -0.00310025 -0.41484 0.909855 +VERTEX_SE3:QUAT 967 -95.9247 204.854 2.46486 -0.0150663 -0.0189305 -0.325478 0.94524 +VERTEX_SE3:QUAT 968 -92.6506 202.337 2.66345 -0.00959702 -0.0241656 -0.297155 0.954475 +VERTEX_SE3:QUAT 969 -89.2782 199.986 2.84522 -0.023656 -0.0222303 -0.298461 0.95387 +VERTEX_SE3:QUAT 970 -85.9586 197.555 3.03605 -0.0168337 -0.0202104 -0.299165 0.953839 +VERTEX_SE3:QUAT 971 -82.309 194.895 3.25233 -0.0134541 -0.0169549 -0.300855 0.953424 +VERTEX_SE3:QUAT 972 -78.8852 192.389 3.45569 -0.0141803 -0.0155398 -0.302158 0.953026 +VERTEX_SE3:QUAT 973 -75.2831 189.724 3.60135 -0.0163247 -0.0228456 -0.304646 0.952052 +VERTEX_SE3:QUAT 974 -72.0818 187.297 3.77114 -0.015137 -0.0223218 -0.310194 0.950291 +VERTEX_SE3:QUAT 975 -68.8681 184.833 3.96905 -0.0127109 -0.0137447 -0.310533 0.950378 +VERTEX_SE3:QUAT 976 -65.6447 182.373 4.14358 -0.0130127 -0.0133218 -0.308594 0.951012 +VERTEX_SE3:QUAT 977 -62.4653 179.961 4.29095 -0.0144764 -0.0169691 -0.306579 0.951584 +VERTEX_SE3:QUAT 978 -59.0027 177.367 4.44923 -0.0142454 -0.0168526 -0.303496 0.952577 +VERTEX_SE3:QUAT 979 -55.485 174.779 4.63369 -0.0130766 -0.0150071 -0.299625 0.953849 +VERTEX_SE3:QUAT 980 -52.1424 172.346 4.82844 -0.0123689 -0.0156457 -0.299401 0.953919 +VERTEX_SE3:QUAT 981 -48.9373 169.847 5.01671 -0.00903172 0.00404228 -0.361447 0.93234 +VERTEX_SE3:QUAT 982 -46.3319 166.641 5.00645 -0.0123206 0.01683 -0.508226 0.860971 +VERTEX_SE3:QUAT 983 -45.1956 162.505 4.97604 -0.0158198 0.0176823 -0.686185 0.72704 +VERTEX_SE3:QUAT 984 -45.7807 158.51 5.0086 -0.0105977 0.0140575 -0.812327 0.582936 +VERTEX_SE3:QUAT 985 -47.9662 154.848 5.00786 -0.00469157 0.0178437 -0.914977 0.403084 +VERTEX_SE3:QUAT 986 -51.2911 152.582 5.01783 -0.00848769 0.0193696 -0.98396 0.17713 +VERTEX_SE3:QUAT 987 -55.3517 152.211 5.08624 0.0119226 -0.0172826 0.997487 0.0676644 +VERTEX_SE3:QUAT 988 -59.3255 153.682 5.22122 -0.0030211 -0.00427351 0.973297 0.22949 +VERTEX_SE3:QUAT 989 -62.9168 155.869 5.214 -0.000346698 -0.00199979 0.959917 0.280276 +VERTEX_SE3:QUAT 990 -66.5887 158.387 5.19787 0.00263856 -0.0040271 0.957072 0.289811 +VERTEX_SE3:QUAT 991 -69.8768 160.703 5.24401 0.00570261 -0.00442162 0.955967 0.293385 +VERTEX_SE3:QUAT 992 -73.2485 163.109 5.33209 0.00233308 -0.00301534 0.955241 0.295803 +VERTEX_SE3:QUAT 993 -76.6541 165.563 5.39404 0.00633544 -0.00254475 0.954778 0.297242 +VERTEX_SE3:QUAT 994 -80.1074 168.07 5.44204 0.0110257 -0.00160875 0.954687 0.297404 +VERTEX_SE3:QUAT 995 -83.4845 170.508 5.50595 -0.00306811 0.00188739 0.954607 0.297848 +VERTEX_SE3:QUAT 996 -86.7689 172.88 5.52316 -0.00921335 0.000995472 0.954151 0.299183 +VERTEX_SE3:QUAT 997 -90.3629 175.489 5.49821 -0.00592097 -0.00262474 0.953686 0.300736 +VERTEX_SE3:QUAT 998 -93.8697 178.056 5.46836 -0.00107829 -0.00592881 0.952929 0.303134 +VERTEX_SE3:QUAT 999 -97.2455 180.562 5.49289 0.00860337 -0.00856522 0.952245 0.305094 +VERTEX_SE3:QUAT 1000 -100.584 183.06 5.59894 0.000187927 -0.00455057 0.95103 0.309065 +VERTEX_SE3:QUAT 1001 -104.008 185.733 5.66209 0.00618868 -0.00304932 0.945167 0.326515 +VERTEX_SE3:QUAT 1002 -107.17 188.53 5.74776 -0.00251545 -0.00133328 0.926953 0.375166 +VERTEX_SE3:QUAT 1003 -109.848 191.663 5.72159 -0.00887809 -0.00438567 0.887332 0.461024 +VERTEX_SE3:QUAT 1004 -111.629 195.275 5.68604 -0.01095 -0.00584968 0.807295 0.590017 +VERTEX_SE3:QUAT 1005 -111.989 199.623 5.66988 -0.00761953 -0.00212433 0.665678 0.746197 +VERTEX_SE3:QUAT 1006 -110.791 203.489 5.66748 -0.00607421 0.000611524 0.543219 0.839569 +VERTEX_SE3:QUAT 1007 -108.62 207.259 5.60149 -0.0099965 0.0072139 0.483017 0.875524 +VERTEX_SE3:QUAT 1008 -106.056 210.867 5.52183 -0.010911 0.00825788 0.460278 0.887669 +VERTEX_SE3:QUAT 1009 -103.625 214.074 5.44379 -0.00995387 0.00688869 0.451401 0.892239 +VERTEX_SE3:QUAT 1010 -101.076 217.287 5.37945 -0.00739388 0.00668439 0.44295 0.896491 +VERTEX_SE3:QUAT 1011 -98.5671 220.367 5.33101 -0.00958877 0.0102816 0.435341 0.900156 +VERTEX_SE3:QUAT 1012 -95.7581 223.679 5.2441 -0.00849919 0.00697323 0.429416 0.90304 +VERTEX_SE3:QUAT 1013 -92.8962 227.035 5.17854 -0.00707082 0.00819172 0.43076 0.902402 +VERTEX_SE3:QUAT 1014 -90.0667 230.379 5.11312 -0.00710047 0.00556814 0.428343 0.903571 +VERTEX_SE3:QUAT 1015 -87.2637 233.409 5.0636 -0.0121091 0.00511112 0.368616 0.929489 +VERTEX_SE3:QUAT 1016 -83.8437 235.784 4.98111 -0.0185148 0.014731 0.234287 0.97188 +VERTEX_SE3:QUAT 1017 -79.8261 236.943 4.87255 -0.0240973 0.00994133 0.0508876 0.998364 +VERTEX_SE3:QUAT 1018 -75.4222 236.393 4.8212 -0.0205991 0.0029221 -0.148622 0.988675 +VERTEX_SE3:QUAT 1019 -71.7577 234.625 4.83652 -0.0106136 0.0180884 -0.26223 0.964777 +VERTEX_SE3:QUAT 1020 -68.189 232.058 4.73416 -0.0126837 0.018655 -0.320018 0.947143 +VERTEX_SE3:QUAT 1021 -65.0714 229.538 4.65797 -0.018183 0.0131236 -0.326627 0.944887 +VERTEX_SE3:QUAT 1022 -61.811 226.886 4.59226 -0.0211039 0.0100616 -0.325479 0.94526 +VERTEX_SE3:QUAT 1023 -58.5789 224.259 4.57652 -0.0196439 0.00814989 -0.322214 0.946428 +VERTEX_SE3:QUAT 1024 -55.3622 221.686 4.59844 -0.0161473 0.0127318 -0.318964 0.947544 +VERTEX_SE3:QUAT 1025 -52.1988 219.191 4.58408 -0.0156378 0.00651469 -0.316926 0.948299 +VERTEX_SE3:QUAT 1026 -49.0409 216.704 4.56885 -0.0150275 0.00477906 -0.31442 0.949153 +VERTEX_SE3:QUAT 1027 -45.8753 214.245 4.55525 -0.0117416 0.0157836 -0.311882 0.949917 +VERTEX_SE3:QUAT 1028 -42.6447 211.767 4.49831 -0.00940215 0.01734 -0.308871 0.950899 +VERTEX_SE3:QUAT 1029 -39.3777 209.303 4.41331 -0.013273 0.0130225 -0.306237 0.951774 +VERTEX_SE3:QUAT 1030 -36.0814 206.828 4.34033 -0.0138763 0.011115 -0.304443 0.952365 +VERTEX_SE3:QUAT 1031 -32.8475 204.413 4.29972 -0.015079 0.0133017 -0.310936 0.950218 +VERTEX_SE3:QUAT 1032 -29.4561 201.653 4.28746 -0.0157737 0.0117335 -0.349005 0.936915 +VERTEX_SE3:QUAT 1033 -26.5275 198.643 4.2896 -0.0155454 0.0154199 -0.417254 0.908526 +VERTEX_SE3:QUAT 1034 -24.1359 195.109 4.22667 -0.0189554 0.0197114 -0.517218 0.855417 +VERTEX_SE3:QUAT 1035 -22.7774 191.274 4.21164 -0.0212698 0.0170482 -0.625722 0.779569 +VERTEX_SE3:QUAT 1036 -22.4998 187.188 4.2593 -0.0173521 0.0133936 -0.722011 0.691534 +VERTEX_SE3:QUAT 1037 -23.2452 183.129 4.29464 -0.0105661 0.0177738 -0.796074 0.604846 +VERTEX_SE3:QUAT 1038 -24.8041 179.199 4.31227 -0.0118087 0.0169626 -0.843006 0.537507 +VERTEX_SE3:QUAT 1039 -26.8408 175.556 4.362 -0.0120265 0.0163054 -0.875583 0.482643 +VERTEX_SE3:QUAT 1040 -29.5915 172.273 4.42861 -0.0131201 0.01201 -0.929528 0.368323 +VERTEX_SE3:QUAT 1041 -33.0104 169.968 4.51998 -0.0121135 0.00843871 -0.975162 0.220998 +VERTEX_SE3:QUAT 1042 -36.9371 168.877 4.6201 -0.0113828 0.0081057 -0.998177 0.0587114 +VERTEX_SE3:QUAT 1043 -41.0304 169.107 4.74675 0.0120719 -0.0070009 0.995506 0.0936637 +VERTEX_SE3:QUAT 1044 -44.8846 170.342 4.88543 0.0074596 0.00426146 0.980325 0.197201 +VERTEX_SE3:QUAT 1045 -48.7407 172.439 4.86311 -0.0243125 0.00829811 0.963076 0.268001 +VERTEX_SE3:QUAT 1046 -52.2391 174.805 4.6617 -0.0223352 0.00930996 0.957188 0.288455 +VERTEX_SE3:QUAT 1047 -55.5029 177.109 4.5085 -0.0237635 0.00729434 0.955631 0.293515 +VERTEX_SE3:QUAT 1048 -59.1092 179.693 4.32503 -0.0202417 0.0079829 0.955091 0.295514 +VERTEX_SE3:QUAT 1049 -62.4498 182.083 4.15271 -0.0177076 0.00730249 0.95531 0.294983 +VERTEX_SE3:QUAT 1050 -65.738 184.441 4.00616 -0.0241217 0.00885461 0.95499 0.295523 +VERTEX_SE3:QUAT 1051 -69.0195 186.806 3.85945 -0.0290352 0.0119413 0.954296 0.29721 +VERTEX_SE3:QUAT 1052 -72.488 189.316 3.64142 -0.0240885 0.00932788 0.95361 0.299935 +VERTEX_SE3:QUAT 1053 -75.7552 191.738 3.44321 -0.0198773 0.00719923 0.95248 0.303865 +VERTEX_SE3:QUAT 1054 -79.1955 194.308 3.26094 -0.0268006 0.0110054 0.951677 0.305732 +VERTEX_SE3:QUAT 1055 -82.4205 196.729 3.07594 -0.0287343 0.0125394 0.951525 0.305969 +VERTEX_SE3:QUAT 1056 -85.6973 199.187 2.86881 -0.0273356 0.0124633 0.951674 0.305636 +VERTEX_SE3:QUAT 1057 -89.0917 201.769 2.63596 -0.0221118 0.0145769 0.951155 0.307575 +VERTEX_SE3:QUAT 1058 -92.5571 204.377 2.41221 -0.0271402 0.0100662 0.94791 0.317221 +VERTEX_SE3:QUAT 1059 -95.8593 207.191 2.22246 -0.012884 0.00510573 0.924072 0.381967 +VERTEX_SE3:QUAT 1060 -98.3343 210.693 2.1304 -0.00979773 0.000857917 0.84367 0.536772 +VERTEX_SE3:QUAT 1061 -99.2116 214.865 2.07107 -0.00670846 0.00289275 0.70221 0.711932 +VERTEX_SE3:QUAT 1062 -98.3502 218.918 2.02748 -0.00900441 0.00241874 0.566105 0.82428 +VERTEX_SE3:QUAT 1063 -96.2556 222.664 1.96511 -0.00646242 0.00514774 0.475277 0.879797 +VERTEX_SE3:QUAT 1064 -93.8091 225.955 1.91549 -0.00746679 0.00446036 0.45134 0.89231 +VERTEX_SE3:QUAT 1065 -91.3089 229.204 1.87774 -0.00601128 0.00430421 0.451873 0.892052 +VERTEX_SE3:QUAT 1066 -88.6907 232.64 1.84025 -0.00608543 0.00226677 0.447995 0.894013 +VERTEX_SE3:QUAT 1067 -86.0568 235.649 1.80483 -0.0135206 0.0116295 0.363376 0.931472 +VERTEX_SE3:QUAT 1068 -82.4956 237.779 1.69923 -0.0173654 0.00910361 0.152304 0.988139 +VERTEX_SE3:QUAT 1069 -78.423 238.069 1.64539 -0.0201839 0.00490642 -0.06712 0.997529 +VERTEX_SE3:QUAT 1070 -74.5573 236.83 1.65054 -0.0162254 0.00158353 -0.20898 0.977784 +VERTEX_SE3:QUAT 1071 -71.0858 234.815 1.65038 -0.0120018 0.0136362 -0.283869 0.958691 +VERTEX_SE3:QUAT 1072 -67.628 232.287 1.58369 -0.0119726 0.0176794 -0.308699 0.95092 +VERTEX_SE3:QUAT 1073 -64.4211 229.854 1.51505 -0.0146557 0.0150206 -0.309368 0.950711 +VERTEX_SE3:QUAT 1074 -61.0666 227.329 1.43816 -0.0179412 0.0119816 -0.308049 0.951126 +VERTEX_SE3:QUAT 1075 -57.747 224.812 1.41413 -0.02081 0.00304013 -0.307798 0.951219 +VERTEX_SE3:QUAT 1076 -54.4156 222.273 1.45841 -0.0145483 0.00923571 -0.31028 0.950489 +VERTEX_SE3:QUAT 1077 -51.0532 219.683 1.45755 -0.0123019 0.00875844 -0.312011 0.949958 +VERTEX_SE3:QUAT 1078 -47.7611 217.132 1.44351 -0.012171 0.00628395 -0.312888 0.949691 +VERTEX_SE3:QUAT 1079 -44.5229 214.622 1.41068 -0.0121169 0.00925573 -0.313791 0.94937 +VERTEX_SE3:QUAT 1080 -41.1402 211.998 1.38621 -0.0107595 0.0171961 -0.313981 0.949213 +VERTEX_SE3:QUAT 1081 -37.994 209.54 1.32368 -0.0111429 0.0166591 -0.31441 0.949076 +VERTEX_SE3:QUAT 1082 -34.5287 206.861 1.24454 -0.01458 0.0113075 -0.314187 0.949182 +VERTEX_SE3:QUAT 1083 -31.3026 204.352 1.21182 -0.0155755 0.00446957 -0.313829 0.949341 +VERTEX_SE3:QUAT 1084 -27.9031 201.673 1.20836 -0.0130846 0.00522519 -0.325463 0.94545 +VERTEX_SE3:QUAT 1085 -24.6874 198.736 1.21824 -0.010516 0.0224087 -0.40445 0.914225 +VERTEX_SE3:QUAT 1086 -22.4312 195.344 1.12462 -0.0186605 0.0189534 -0.537108 0.843094 +VERTEX_SE3:QUAT 1087 -21.397 191.391 1.11748 -0.0199961 0.0150144 -0.672546 0.739633 +VERTEX_SE3:QUAT 1088 -21.731 187.376 1.17662 -0.0166202 0.0110013 -0.787736 0.61569 +VERTEX_SE3:QUAT 1089 -23.4467 183.594 1.23058 -0.00863202 0.0103356 -0.86875 0.495068 +VERTEX_SE3:QUAT 1090 -25.8712 180.146 1.26892 -0.00924616 0.00965695 -0.887827 0.459984 +VERTEX_SE3:QUAT 1091 -28.2582 176.921 1.31679 -0.0100343 0.00992765 -0.887184 0.461199 +VERTEX_SE3:QUAT 1092 -30.673 173.627 1.36523 -0.0118115 0.00774833 -0.88598 0.463507 +VERTEX_SE3:QUAT 1093 -33.0448 170.337 1.43861 -0.00885529 0.00974751 -0.884689 0.465995 +VERTEX_SE3:QUAT 1094 -35.4378 166.984 1.4887 -0.01136 0.00950188 -0.883201 0.46876 +VERTEX_SE3:QUAT 1095 -37.9778 163.383 1.55881 -0.0103925 0.00950492 -0.881532 0.471915 +VERTEX_SE3:QUAT 1096 -40.4207 159.887 1.62648 -0.0124947 0.00862513 -0.88531 0.464753 +VERTEX_SE3:QUAT 1097 -43.1048 156.497 1.72377 -0.0117559 0.00738542 -0.914537 0.404264 +VERTEX_SE3:QUAT 1098 -46.4275 153.792 1.77733 -0.00356642 0.0143061 -0.967027 0.254248 +VERTEX_SE3:QUAT 1099 -50.5145 152.511 1.80267 -0.00773431 0.0133678 -0.998215 0.0576965 +VERTEX_SE3:QUAT 1100 -54.5057 152.805 1.88319 0.0113076 -0.0118699 0.99384 0.109603 +VERTEX_SE3:QUAT 1101 -58.4254 154.373 2.01235 -0.000242946 -0.000625335 0.972922 0.231132 +VERTEX_SE3:QUAT 1102 -61.9549 156.51 2.00628 -0.00142562 -0.00180814 0.960303 0.278948 +VERTEX_SE3:QUAT 1103 -65.62 159.058 1.97927 -0.000825994 -0.00493588 0.953982 0.299822 +VERTEX_SE3:QUAT 1104 -68.7983 161.459 1.98776 0.0064187 -0.00458127 0.950888 0.309435 +VERTEX_SE3:QUAT 1105 -72.046 163.955 2.07641 0.00343575 -0.0034491 0.949779 0.312883 +VERTEX_SE3:QUAT 1106 -75.1987 166.405 2.14239 0.00710526 -0.00214577 0.949672 0.313157 +VERTEX_SE3:QUAT 1107 -78.705 169.133 2.19249 0.00671819 -0.00178401 0.94971 0.313053 +VERTEX_SE3:QUAT 1108 -81.9808 171.655 2.23285 -0.00209702 0.000663266 0.949711 0.313119 +VERTEX_SE3:QUAT 1109 -85.2163 174.165 2.25249 -0.00808832 0.000200167 0.94958 0.31342 +VERTEX_SE3:QUAT 1110 -88.7689 176.891 2.21626 -0.00589559 -0.00276355 0.950145 0.311739 +VERTEX_SE3:QUAT 1111 -92.0026 179.365 2.19366 -0.00408735 -0.00617187 0.950718 0.309967 +VERTEX_SE3:QUAT 1112 -95.4542 181.991 2.20501 0.00550599 -0.00771108 0.95155 0.307348 +VERTEX_SE3:QUAT 1113 -98.8687 184.55 2.27573 -0.00116364 -0.00335716 0.952346 0.305001 +VERTEX_SE3:QUAT 1114 -102.22 187.033 2.32011 0.00224726 -0.00434796 0.952493 0.30452 +VERTEX_SE3:QUAT 1115 -105.621 189.693 2.38493 0.00340223 -0.00123123 0.940876 0.338732 +VERTEX_SE3:QUAT 1116 -108.709 192.758 2.36344 -0.0100771 -0.00369171 0.902068 0.431461 +VERTEX_SE3:QUAT 1117 -110.724 196.485 2.30775 -0.0116709 -0.00557699 0.807299 0.590001 +VERTEX_SE3:QUAT 1118 -111.116 200.74 2.27974 -0.00915935 -0.00584817 0.671062 0.741321 +VERTEX_SE3:QUAT 1119 -109.774 204.939 2.27959 -0.0139239 0.00721629 0.534165 0.845235 +VERTEX_SE3:QUAT 1120 -107.518 208.557 2.17374 -0.0143098 0.00638039 0.462377 0.886545 +VERTEX_SE3:QUAT 1121 -104.761 212.004 2.08769 -0.0120569 0.00698748 0.436631 0.899533 +VERTEX_SE3:QUAT 1122 -102.207 215.1 2.01452 -0.0076368 0.00499508 0.437528 0.899159 +VERTEX_SE3:QUAT 1123 -99.6909 218.222 1.96268 -0.00777717 0.00314572 0.443292 0.896338 +VERTEX_SE3:QUAT 1124 -97.141 221.404 1.91915 -0.00856321 0.00780451 0.442636 0.896627 +VERTEX_SE3:QUAT 1125 -94.3846 224.807 1.8518 -0.00675034 0.00683156 0.439948 0.897972 +VERTEX_SE3:QUAT 1126 -91.6678 228.135 1.80127 -0.00520482 0.0043529 0.438646 0.898635 +VERTEX_SE3:QUAT 1127 -88.9738 231.436 1.76334 -0.00533978 0.00148672 0.43945 0.89825 +VERTEX_SE3:QUAT 1128 -86.3218 234.745 1.7435 -0.00949766 0.0132145 0.44572 0.895024 +VERTEX_SE3:QUAT 1129 -83.6928 238.145 1.62247 -0.0102569 0.0125831 0.45409 0.890808 +VERTEX_SE3:QUAT 1130 -81.1138 241.607 1.50987 -0.0105749 0.0124636 0.462637 0.886397 +VERTEX_SE3:QUAT 1131 -78.6284 245.092 1.41035 -0.0100724 0.00868981 0.466136 0.884613 +VERTEX_SE3:QUAT 1132 -75.9887 248.517 1.32614 -0.0143314 0.00692803 0.411549 0.911249 +VERTEX_SE3:QUAT 1133 -72.6427 251.276 1.23574 -0.0157314 0.00829973 0.258396 0.965875 +VERTEX_SE3:QUAT 1134 -68.6246 252.538 1.16932 -0.0207475 0.00249469 0.0452297 0.998758 +VERTEX_SE3:QUAT 1135 -64.3337 252.001 1.17856 -0.0211147 -0.00215396 -0.151075 0.988294 +VERTEX_SE3:QUAT 1136 -60.632 250.239 1.22123 -0.0131053 0.0147891 -0.252267 0.967456 +VERTEX_SE3:QUAT 1137 -56.9287 247.833 1.15613 -0.00716347 0.0130486 -0.283167 0.958955 +VERTEX_SE3:QUAT 1138 -53.5881 245.502 1.09643 -0.00667907 0.00487049 -0.294441 0.955634 +VERTEX_SE3:QUAT 1139 -50.1921 243.039 1.06851 -0.00443391 0.00371128 -0.300437 0.953784 +VERTEX_SE3:QUAT 1140 -46.7876 240.512 1.07068 -0.00309895 0.00364215 -0.30462 0.952462 +VERTEX_SE3:QUAT 1141 -43.3992 237.998 1.0818 -0.00703083 0.00416268 -0.305532 0.952147 +VERTEX_SE3:QUAT 1142 -40.0349 235.477 1.09722 -0.0102794 0.00439591 -0.305867 0.952009 +VERTEX_SE3:QUAT 1143 -36.793 233.038 1.08334 -0.0106311 0.00268308 -0.305644 0.952083 +VERTEX_SE3:QUAT 1144 -33.1468 230.307 1.07674 -0.0106645 0.00651057 -0.304546 0.952416 +VERTEX_SE3:QUAT 1145 -29.5855 227.644 1.05725 -0.00792843 0.0135211 -0.30339 0.952738 +VERTEX_SE3:QUAT 1146 -26.0814 225.04 1.00044 -0.00427429 0.0129284 -0.3018 0.953274 +VERTEX_SE3:QUAT 1147 -22.6322 222.5 0.935494 -0.0054433 0.00795203 -0.300361 0.953777 +VERTEX_SE3:QUAT 1148 -19.306 220.073 0.8979 -0.00846434 0.00252254 -0.300301 0.953804 +VERTEX_SE3:QUAT 1149 -15.8497 217.48 0.892895 -0.0126876 0.00701528 -0.327366 0.944787 +VERTEX_SE3:QUAT 1150 -12.7976 214.53 0.897794 -0.0121743 0.0231002 -0.423659 0.905445 +VERTEX_SE3:QUAT 1151 -10.7482 210.877 0.812365 -0.0141282 0.0162919 -0.573804 0.818709 +VERTEX_SE3:QUAT 1152 -10.1115 206.506 0.809889 -0.0171414 0.0115471 -0.718262 0.695466 +VERTEX_SE3:QUAT 1153 -10.9895 202.566 0.868674 -0.0156348 0.00778491 -0.819266 0.573147 +VERTEX_SE3:QUAT 1154 -12.9078 198.956 0.9357 -0.00948031 0.00565088 -0.872472 0.488539 +VERTEX_SE3:QUAT 1155 -15.2897 195.534 1.00829 -0.00930475 0.00373142 -0.886742 0.462157 +VERTEX_SE3:QUAT 1156 -17.8211 192.156 1.09134 -0.0126741 0.00143922 -0.892759 0.450353 +VERTEX_SE3:QUAT 1157 -20.3513 188.895 1.18511 -0.016621 0.00595199 -0.894956 0.445805 +VERTEX_SE3:QUAT 1158 -22.8892 185.661 1.30297 -0.00492595 0.00957857 -0.893094 0.449742 +VERTEX_SE3:QUAT 1159 -25.4243 182.393 1.3191 -0.00664647 0.00669512 -0.892329 0.451288 +VERTEX_SE3:QUAT 1160 -27.9786 179.064 1.35527 -0.00652075 0.00700512 -0.891189 0.453531 +VERTEX_SE3:QUAT 1161 -30.5548 175.7 1.40244 -0.00597659 0.00746444 -0.890912 0.454076 +VERTEX_SE3:QUAT 1162 -33.1064 172.309 1.45037 -0.00890511 0.00895439 -0.890349 0.455104 +VERTEX_SE3:QUAT 1163 -35.7225 168.857 1.49825 -0.00808942 0.00803957 -0.889934 0.455946 +VERTEX_SE3:QUAT 1164 -38.2779 165.489 1.55065 -0.00714689 0.00499123 -0.889453 0.456943 +VERTEX_SE3:QUAT 1165 -40.8036 162.13 1.60208 -0.00939548 0.00464471 -0.888807 0.458161 +VERTEX_SE3:QUAT 1166 -43.2625 158.817 1.67006 -0.0121283 0.00603137 -0.888341 0.458984 +VERTEX_SE3:QUAT 1167 -45.6499 155.606 1.75668 0.00198132 0.0104782 -0.887612 0.460468 +VERTEX_SE3:QUAT 1168 -48.1036 152.274 1.72329 -0.000457724 0.0085045 -0.886145 0.46333 +VERTEX_SE3:QUAT 1169 -50.5139 148.928 1.72163 -0.00224717 0.00816949 -0.884036 0.467343 +VERTEX_SE3:QUAT 1170 -52.9207 145.54 1.72932 -0.0046835 0.00893804 -0.883248 0.468798 +VERTEX_SE3:QUAT 1171 -55.3146 142.194 1.7457 -0.00809243 0.00620563 -0.888836 0.458111 +VERTEX_SE3:QUAT 1172 -58.0522 138.878 1.78428 -0.00548918 0.0127189 -0.922185 0.3865 +VERTEX_SE3:QUAT 1173 -61.5164 136.431 1.81105 -0.00631278 0.0127271 -0.97826 0.206896 +VERTEX_SE3:QUAT 1174 -65.5566 135.619 1.86457 0.00997898 -0.0114268 0.999884 0.00123527 +VERTEX_SE3:QUAT 1175 -69.7759 136.534 1.94729 0.0116949 -0.00828429 0.981932 0.188691 +VERTEX_SE3:QUAT 1176 -73.3984 138.643 2.02527 -0.000671234 -0.0014556 0.953823 0.300365 +VERTEX_SE3:QUAT 1177 -76.6911 141.34 2.03605 -0.0022039 0.0025122 0.941517 0.336949 +VERTEX_SE3:QUAT 1178 -79.9491 144.195 2.04069 0.00536215 0.00350346 0.940574 0.339527 +VERTEX_SE3:QUAT 1179 -83.2315 147.044 2.07911 0.00688137 0.00191462 0.941415 0.337174 +VERTEX_SE3:QUAT 1180 -86.2921 149.635 2.122 0.00536706 -0.00169518 0.943516 0.33128 +VERTEX_SE3:QUAT 1181 -89.6819 152.43 2.18659 0.000983915 0.00132384 0.946534 0.3226 +VERTEX_SE3:QUAT 1182 -93.1856 155.205 2.22834 -0.00327946 0.00336156 0.948885 0.315588 +VERTEX_SE3:QUAT 1183 -96.7762 157.99 2.21933 -0.00230531 0.002684 0.950329 0.311228 +VERTEX_SE3:QUAT 1184 -100.273 160.672 2.19861 -0.00069472 0.00324456 0.95104 0.30905 +VERTEX_SE3:QUAT 1185 -103.843 163.392 2.17069 9.58441e-05 0.0064834 0.9518 0.30665 +VERTEX_SE3:QUAT 1186 -107.136 165.865 2.17087 0.00381372 0.00516298 0.952456 0.304608 +VERTEX_SE3:QUAT 1187 -110.494 168.354 2.20936 -0.00244987 0.0040076 0.951153 0.308684 +VERTEX_SE3:QUAT 1188 -113.662 170.837 2.21657 0.00371881 0.000987967 0.94527 0.326267 +VERTEX_SE3:QUAT 1189 -116.974 173.756 2.25039 0.00319401 -0.00420784 0.92615 0.377118 +VERTEX_SE3:QUAT 1190 -119.576 176.866 2.2749 -0.0168381 -0.00116712 0.88394 0.467295 +VERTEX_SE3:QUAT 1191 -121.315 180.781 2.19151 -0.0132561 -0.00321032 0.79039 0.612452 +VERTEX_SE3:QUAT 1192 -121.535 185.21 2.13456 -0.00818394 -0.00449586 0.665008 0.746777 +VERTEX_SE3:QUAT 1193 -120.299 189.381 2.1289 -0.0116557 0.000771297 0.547075 0.837002 +VERTEX_SE3:QUAT 1194 -118.274 192.811 2.09392 -0.00518834 -9.84238e-05 0.477775 0.878467 +VERTEX_SE3:QUAT 1195 -115.965 196.112 2.09065 -0.00522534 -2.8421e-05 0.470074 0.882612 +VERTEX_SE3:QUAT 1196 -113.614 199.477 2.09329 -0.0054895 -0.00125601 0.470989 0.882121 +VERTEX_SE3:QUAT 1197 -111.299 202.797 2.09547 -0.00571867 -0.0031165 0.471939 0.881607 +VERTEX_SE3:QUAT 1198 -108.996 206.095 2.07951 -0.0102789 0.00735556 0.473626 0.880636 +VERTEX_SE3:QUAT 1199 -106.516 209.706 2.00214 -0.0119708 0.00528511 0.47567 0.879526 +VERTEX_SE3:QUAT 1200 -104.034 213.303 1.9338 -0.0126501 0.00352506 0.469048 0.883075 +VERTEX_SE3:QUAT 1201 -101.518 216.662 1.88181 -0.0104973 0.0025669 0.435895 0.899933 +VERTEX_SE3:QUAT 1202 -98.689 219.613 1.84807 -0.010069 0.00526939 0.347922 0.937455 +VERTEX_SE3:QUAT 1203 -94.9724 221.828 1.78876 -0.0131937 0.00287934 0.173929 0.984666 +VERTEX_SE3:QUAT 1204 -90.9103 222.431 1.78632 -0.0163315 -0.00357264 -0.0232008 0.999591 +VERTEX_SE3:QUAT 1205 -86.9538 221.443 1.84492 -0.0150718 -0.00409448 -0.202134 0.979233 +VERTEX_SE3:QUAT 1206 -83.1712 219.142 1.80785 0.000233671 0.0316197 -0.295737 0.954746 +VERTEX_SE3:QUAT 1207 -79.934 216.717 1.59455 -0.000762864 0.0340764 -0.310586 0.949934 +VERTEX_SE3:QUAT 1208 -76.6263 214.154 1.36565 -8.88865e-05 0.0307971 -0.312724 0.949345 +VERTEX_SE3:QUAT 1209 -73.0928 211.43 1.10154 -0.00208336 0.024103 -0.309225 0.950681 +VERTEX_SE3:QUAT 1210 -69.8928 209.013 0.889421 0.000156702 0.0251773 -0.304547 0.952164 +VERTEX_SE3:QUAT 1211 -66.4803 206.471 0.704488 0.00240553 0.0345399 -0.304804 0.951786 +VERTEX_SE3:QUAT 1212 -62.9664 203.837 0.459944 0.00166074 0.0323492 -0.306158 0.95143 +VERTEX_SE3:QUAT 1213 -59.5055 201.244 0.211328 -0.00146938 0.0322345 -0.306694 0.951261 +VERTEX_SE3:QUAT 1214 -56.3048 198.804 -0.0298242 -0.000278195 0.0324088 -0.306543 0.951305 +VERTEX_SE3:QUAT 1215 -52.7582 196.149 -0.284989 0.00313685 0.0375964 -0.305341 0.951496 +VERTEX_SE3:QUAT 1216 -49.4044 193.653 -0.52644 0.00239718 0.039462 -0.301897 0.952521 +VERTEX_SE3:QUAT 1217 -46.1425 191.246 -0.783344 0.00335254 0.0345075 -0.299447 0.953483 +VERTEX_SE3:QUAT 1218 -42.7658 188.804 -1.0655 -0.000811834 0.0310016 -0.298412 0.953933 +VERTEX_SE3:QUAT 1219 -39.4953 186.389 -1.29807 0.0021443 0.0368432 -0.311183 0.949633 +VERTEX_SE3:QUAT 1220 -36.3505 183.716 -1.54884 -0.0048966 0.0170772 -0.385125 0.922693 +VERTEX_SE3:QUAT 1221 -33.9453 180.263 -1.64359 -0.00625741 0.0177339 -0.535155 0.844545 +VERTEX_SE3:QUAT 1222 -32.9578 176.382 -1.71393 -0.0102179 0.0144407 -0.677896 0.734945 +VERTEX_SE3:QUAT 1223 -33.4292 172.316 -1.70775 -0.00503818 0.01137 -0.793007 0.609086 +VERTEX_SE3:QUAT 1224 -35.1045 168.33 -1.72905 -0.00811223 0.0113692 -0.855597 0.517454 +VERTEX_SE3:QUAT 1225 -37.2481 164.828 -1.70181 -0.00843923 0.0113988 -0.872131 0.489067 +VERTEX_SE3:QUAT 1226 -39.6303 161.171 -1.66177 -0.00860766 0.0120001 -0.878494 0.477525 +VERTEX_SE3:QUAT 1227 -42.0076 157.95 -1.61988 -0.0103675 0.0095533 -0.903053 0.429298 +VERTEX_SE3:QUAT 1228 -44.9811 155.078 -1.55672 0.000436405 0.0141957 -0.948894 0.315277 +VERTEX_SE3:QUAT 1229 -48.483 153.218 -1.56485 0.000242024 0.0167625 -0.985735 0.16747 +VERTEX_SE3:QUAT 1230 -52.7017 152.569 -1.54358 0.00423035 -0.0153698 0.999814 0.0108321 +VERTEX_SE3:QUAT 1231 -56.731 153.351 -1.4776 0.0114074 -0.0111989 0.987562 0.156417 +VERTEX_SE3:QUAT 1232 -60.5312 155.158 -1.43192 -0.00663648 -0.00415477 0.967023 0.25457 +VERTEX_SE3:QUAT 1233 -63.9482 157.383 -1.45949 -0.00701705 -0.0081517 0.95711 0.289525 +VERTEX_SE3:QUAT 1234 -67.3039 159.813 -1.471 -0.00135071 -0.00689423 0.952172 0.305482 +VERTEX_SE3:QUAT 1235 -70.7701 162.44 -1.42854 0.00698073 -0.00960742 0.950239 0.311295 +VERTEX_SE3:QUAT 1236 -74.2039 165.086 -1.36583 0.00499158 -0.00643509 0.950269 0.311324 +VERTEX_SE3:QUAT 1237 -77.6861 167.768 -1.3036 0.00116559 -0.00334203 0.950839 0.309665 +VERTEX_SE3:QUAT 1238 -81.1701 170.399 -1.25103 -0.00824903 -0.000804093 0.951346 0.308014 +VERTEX_SE3:QUAT 1239 -84.3707 172.817 -1.28355 -0.00561181 -0.00414778 0.952024 0.305945 +VERTEX_SE3:QUAT 1240 -87.8923 175.436 -1.32694 -0.00487487 -0.00803322 0.952868 0.303241 +VERTEX_SE3:QUAT 1241 -91.4321 178.039 -1.34375 -0.00761555 -0.00729677 0.953938 0.299818 +VERTEX_SE3:QUAT 1242 -94.9106 180.564 -1.35087 -0.00611994 -0.00776379 0.954261 0.298813 +VERTEX_SE3:QUAT 1243 -98.4739 183.171 -1.3305 -0.0030276 -0.00737789 0.952803 0.303483 +VERTEX_SE3:QUAT 1244 -101.839 185.72 -1.30818 0.003921 -0.00984406 0.949748 0.312837 +VERTEX_SE3:QUAT 1245 -105.105 188.339 -1.25084 0.00591091 -0.0084666 0.941859 0.33585 +VERTEX_SE3:QUAT 1246 -108.194 191.231 -1.18999 -0.0165118 -0.0047572 0.914363 0.404531 +VERTEX_SE3:QUAT 1247 -110.451 194.615 -1.25797 -0.0155903 -0.00609106 0.843101 0.537495 +VERTEX_SE3:QUAT 1248 -111.393 198.832 -1.29803 -0.00636997 -0.0080346 0.714969 0.699081 +VERTEX_SE3:QUAT 1249 -110.654 202.864 -1.27851 -0.00854877 -0.00356501 0.573108 0.819428 +VERTEX_SE3:QUAT 1250 -108.646 206.553 -1.30979 -0.0088614 0.00132886 0.47943 0.877534 +VERTEX_SE3:QUAT 1251 -106.247 209.803 -1.34343 -0.0102054 0.00407846 0.449393 0.893267 +VERTEX_SE3:QUAT 1252 -103.681 213.068 -1.38521 -0.00771321 0.00278345 0.447288 0.894353 +VERTEX_SE3:QUAT 1253 -101.057 216.421 -1.4196 -0.00684376 0.00280111 0.44876 0.893622 +VERTEX_SE3:QUAT 1254 -98.5351 219.669 -1.44877 -0.00554489 0.00206508 0.450694 0.892659 +VERTEX_SE3:QUAT 1255 -96.0854 222.857 -1.46867 -0.00749877 0.00286594 0.452629 0.891663 +VERTEX_SE3:QUAT 1256 -93.6793 226.025 -1.48493 -0.00698343 0.00197376 0.455095 0.890413 +VERTEX_SE3:QUAT 1257 -91.2373 229.292 -1.49646 -0.00589192 -0.000695503 0.456875 0.889511 +VERTEX_SE3:QUAT 1258 -88.7809 232.473 -1.51099 -0.00934069 -0.00141479 0.427838 0.903806 +VERTEX_SE3:QUAT 1259 -85.937 235.314 -1.53168 -0.0154909 0.00533475 0.330343 0.943719 +VERTEX_SE3:QUAT 1260 -82.1493 237.31 -1.59473 -0.0192409 0.00440518 0.151405 0.988275 +VERTEX_SE3:QUAT 1261 -78.1787 237.75 -1.61632 -0.0160994 0.000510101 -0.0300596 0.999418 +VERTEX_SE3:QUAT 1262 -74.2538 236.708 -1.58718 -0.0122763 0.00117808 -0.200167 0.979684 +VERTEX_SE3:QUAT 1263 -70.5697 234.573 -1.60785 -0.0110409 0.00728508 -0.287085 0.957814 +VERTEX_SE3:QUAT 1264 -67.2502 232.142 -1.64521 -0.0101987 0.0131305 -0.308909 0.950946 +VERTEX_SE3:QUAT 1265 -63.8577 229.538 -1.68198 -0.0121248 0.0132135 -0.313424 0.949444 +VERTEX_SE3:QUAT 1266 -60.3865 226.854 -1.7335 -0.0168935 0.00723704 -0.315012 0.94891 +VERTEX_SE3:QUAT 1267 -56.9932 224.204 -1.71938 -0.0172641 0.000750727 -0.314704 0.949033 +VERTEX_SE3:QUAT 1268 -53.6777 221.608 -1.67854 -0.0147188 0.00199369 -0.313651 0.949422 +VERTEX_SE3:QUAT 1269 -50.4506 219.093 -1.63594 -0.0100752 0.00748941 -0.312762 0.949748 +VERTEX_SE3:QUAT 1270 -47.0998 216.506 -1.62779 -0.00855489 0.00980565 -0.310476 0.950492 +VERTEX_SE3:QUAT 1271 -43.7285 213.937 -1.66933 -0.0102237 0.00770844 -0.308345 0.951189 +VERTEX_SE3:QUAT 1272 -40.2683 211.328 -1.71152 -0.0105524 0.00958576 -0.305987 0.951929 +VERTEX_SE3:QUAT 1273 -36.7239 208.686 -1.76683 -0.0113151 0.0141177 -0.30335 0.952707 +VERTEX_SE3:QUAT 1274 -33.2045 206.104 -1.81358 -0.0128635 0.0103751 -0.300612 0.953603 +VERTEX_SE3:QUAT 1275 -29.8679 203.653 -1.80841 -0.0106961 0.00697174 -0.30684 0.951675 +VERTEX_SE3:QUAT 1276 -26.4641 200.904 -1.80611 -0.0139731 0.00426997 -0.35717 0.933925 +VERTEX_SE3:QUAT 1277 -23.7586 197.795 -1.81491 -0.011371 0.0196367 -0.476014 0.879145 +VERTEX_SE3:QUAT 1278 -22.1772 194.124 -1.86996 -0.0148679 0.0133243 -0.611893 0.790688 +VERTEX_SE3:QUAT 1279 -21.8914 189.781 -1.84664 -0.0186827 0.0104938 -0.745099 0.666609 +VERTEX_SE3:QUAT 1280 -23.0232 185.887 -1.77614 -0.00578447 0.0128174 -0.832503 0.553843 +VERTEX_SE3:QUAT 1281 -25.1436 182.081 -1.78422 -0.00435843 0.00876476 -0.872917 0.487771 +VERTEX_SE3:QUAT 1282 -27.4322 178.656 -1.7659 -0.00578737 0.00997051 -0.880083 0.474681 +VERTEX_SE3:QUAT 1283 -29.7055 175.392 -1.74169 -0.00774566 0.0101246 -0.882141 0.470813 +VERTEX_SE3:QUAT 1284 -32.0353 172.089 -1.70685 -0.00870865 0.00804286 -0.883326 0.468609 +VERTEX_SE3:QUAT 1285 -34.3986 168.772 -1.69733 -0.00751468 0.00933573 -0.884164 0.467023 +VERTEX_SE3:QUAT 1286 -36.7205 165.514 -1.66315 -0.00845771 0.0104164 -0.884977 0.465442 +VERTEX_SE3:QUAT 1287 -39.0582 162.28 -1.62205 -0.00947774 0.0106166 -0.885756 0.463934 +VERTEX_SE3:QUAT 1288 -41.587 158.811 -1.56722 -0.0104565 0.00831677 -0.886595 0.462354 +VERTEX_SE3:QUAT 1289 -44.1043 155.345 -1.49816 -0.00201151 0.012371 -0.887187 0.46124 +VERTEX_SE3:QUAT 1290 -46.4619 152.134 -1.512 -0.00127881 0.0127877 -0.887692 0.460258 +VERTEX_SE3:QUAT 1291 -49.0636 148.598 -1.53438 -0.00304508 0.0141333 -0.888178 0.459272 +VERTEX_SE3:QUAT 1292 -51.7251 145.076 -1.54377 -0.00550859 0.0128487 -0.896008 0.443817 +VERTEX_SE3:QUAT 1293 -54.5633 141.802 -1.53563 -0.00727337 0.012534 -0.921338 0.388493 +VERTEX_SE3:QUAT 1294 -57.8665 139.175 -1.50892 -0.00206348 0.0132999 -0.96425 0.264651 +VERTEX_SE3:QUAT 1295 -61.8775 137.672 -1.48498 -0.00594337 0.0118729 -0.995131 0.0976578 +VERTEX_SE3:QUAT 1296 -66.1126 137.631 -1.41602 0.00908539 -0.0137281 0.996876 0.0772502 +VERTEX_SE3:QUAT 1297 -70.2401 139.058 -1.29302 -0.00605831 -0.00573708 0.974455 0.224428 +VERTEX_SE3:QUAT 1298 -73.6537 141.221 -1.31332 -0.00159847 0.000555935 0.95432 0.298782 +VERTEX_SE3:QUAT 1299 -77.0599 143.811 -1.32909 0.00340672 0.000165094 0.94946 0.313869 +VERTEX_SE3:QUAT 1300 -80.5461 146.56 -1.30921 0.00693702 -0.000135941 0.946617 0.322287 +VERTEX_SE3:QUAT 1301 -83.8851 149.279 -1.23047 0.00111068 -0.00188078 0.944514 0.328465 +VERTEX_SE3:QUAT 1302 -87.1284 151.976 -1.17454 0.000946187 -0.00256491 0.94412 0.329589 +VERTEX_SE3:QUAT 1303 -90.3138 154.614 -1.14959 0.00396021 -0.00178445 0.945841 0.324601 +VERTEX_SE3:QUAT 1304 -93.5853 157.236 -1.14017 -0.000638287 0.00191035 0.949512 0.313724 +VERTEX_SE3:QUAT 1305 -97.0365 159.848 -1.1482 -0.00682782 0.0027399 0.95346 0.30143 +VERTEX_SE3:QUAT 1306 -100.519 162.374 -1.17061 -0.00670784 0.00984553 0.95716 0.289313 +VERTEX_SE3:QUAT 1307 -104.071 164.792 -1.21467 0.00011108 0.00644857 0.959989 0.279963 +VERTEX_SE3:QUAT 1308 -107.542 167.078 -1.20103 0.00517911 0.00322234 0.961211 0.275748 +VERTEX_SE3:QUAT 1309 -111.205 169.456 -1.16398 0.00155206 -0.000338938 0.960687 0.27763 +VERTEX_SE3:QUAT 1310 -114.629 171.81 -1.11716 0.00055278 -0.0037915 0.951151 0.308704 +VERTEX_SE3:QUAT 1311 -117.698 174.469 -1.07997 -0.00707893 -0.00556349 0.921406 0.388497 +VERTEX_SE3:QUAT 1312 -120.156 177.793 -1.1283 -0.0142716 -0.00260913 0.861319 0.507857 +VERTEX_SE3:QUAT 1313 -121.531 181.874 -1.19548 -0.00878355 -0.00321901 0.763187 0.64611 +VERTEX_SE3:QUAT 1314 -121.428 186.136 -1.20294 -0.0101006 -0.00320154 0.638327 0.769693 +VERTEX_SE3:QUAT 1315 -119.938 190.106 -1.21623 -0.00864873 -0.00210723 0.521513 0.853197 +VERTEX_SE3:QUAT 1316 -117.537 193.72 -1.22376 -0.00504612 -0.00064179 0.459968 0.887921 +VERTEX_SE3:QUAT 1317 -115.112 196.913 -1.22638 -0.00370808 -0.00162615 0.452464 0.891773 +VERTEX_SE3:QUAT 1318 -112.645 200.141 -1.21767 -0.00477045 -0.00265179 0.453663 0.891157 +VERTEX_SE3:QUAT 1319 -110.148 203.447 -1.20017 -0.00839651 0.00282359 0.455958 0.889957 +VERTEX_SE3:QUAT 1320 -107.674 206.731 -1.25832 -0.00594174 0.00451443 0.456304 0.889793 +VERTEX_SE3:QUAT 1321 -105.167 210.067 -1.3032 -0.00841821 0.00596773 0.456463 0.889682 +VERTEX_SE3:QUAT 1322 -102.672 213.375 -1.35625 -0.00730718 0.00482816 0.457362 0.889238 +VERTEX_SE3:QUAT 1323 -100.213 216.669 -1.40084 -0.0073988 0.00324924 0.458496 0.88866 +VERTEX_SE3:QUAT 1324 -97.7729 219.948 -1.4351 -0.00580612 0.00392949 0.45986 0.887964 +VERTEX_SE3:QUAT 1325 -95.1939 223.434 -1.47044 -0.00608861 0.00445717 0.461781 0.886962 +VERTEX_SE3:QUAT 1326 -92.6886 226.862 -1.50474 -0.0070854 0.00293477 0.463461 0.886084 +VERTEX_SE3:QUAT 1327 -90.1843 230.312 -1.54217 -0.00737758 0.000496136 0.464365 0.885613 +VERTEX_SE3:QUAT 1328 -87.7413 233.7 -1.56588 -0.0108535 0.00425964 0.465004 0.885232 +VERTEX_SE3:QUAT 1329 -85.2432 237.155 -1.64129 -0.0111022 0.00783932 0.465663 0.884858 +VERTEX_SE3:QUAT 1330 -82.6846 240.705 -1.73208 -0.0113548 0.0074589 0.465884 0.884741 +VERTEX_SE3:QUAT 1331 -80.128 244.22 -1.81325 -0.0128336 0.00682553 0.453445 0.891166 +VERTEX_SE3:QUAT 1332 -77.3387 247.583 -1.89153 -0.0104622 0.00454708 0.401306 0.915873 +VERTEX_SE3:QUAT 1333 -74.1223 250.359 -1.94934 -0.0160497 0.00721312 0.292716 0.956037 +VERTEX_SE3:QUAT 1334 -70.1693 252.144 -2.02488 -0.0191566 0.00439731 0.125347 0.991918 +VERTEX_SE3:QUAT 1335 -65.8568 252.407 -2.04381 -0.0207391 -9.34095e-05 -0.0567551 0.998173 +VERTEX_SE3:QUAT 1336 -61.6514 251.122 -1.97706 -0.0143898 0.0125776 -0.213514 0.976753 +VERTEX_SE3:QUAT 1337 -58.25 249.021 -2.02901 -0.00653988 0.00730416 -0.294876 0.955485 +VERTEX_SE3:QUAT 1338 -54.8333 246.456 -2.08398 -0.00527115 0.00302921 -0.309778 0.950789 +VERTEX_SE3:QUAT 1339 -51.3084 243.743 -2.10081 -0.00266509 0.0083327 -0.311054 0.950352 +VERTEX_SE3:QUAT 1340 -47.8548 241.097 -2.12455 -0.00370815 0.00327209 -0.310528 0.950551 +VERTEX_SE3:QUAT 1341 -44.2969 238.39 -2.09458 -0.00501178 0.00114627 -0.308131 0.95133 +VERTEX_SE3:QUAT 1342 -40.8249 235.793 -2.07668 -0.00868108 0.000241535 -0.304705 0.952407 +VERTEX_SE3:QUAT 1343 -37.3441 233.217 -2.06261 -0.00802106 0.000948759 -0.300717 0.953679 +VERTEX_SE3:QUAT 1344 -33.7929 230.645 -2.05203 -0.00770892 0.00875659 -0.295629 0.955232 +VERTEX_SE3:QUAT 1345 -30.2711 228.135 -2.07791 -0.00377641 0.0104724 -0.289354 0.957158 +VERTEX_SE3:QUAT 1346 -26.7841 225.734 -2.12382 -0.00394671 0.0114102 -0.282797 0.959104 +VERTEX_SE3:QUAT 1347 -23.4072 223.472 -2.18811 -0.00492219 0.00560173 -0.278569 0.960387 +VERTEX_SE3:QUAT 1348 -19.765 221.015 -2.20425 -0.00499731 0.00534022 -0.292758 0.956159 +VERTEX_SE3:QUAT 1349 -16.444 218.487 -2.21897 -0.0104007 0.00540151 -0.337618 0.94121 +VERTEX_SE3:QUAT 1350 -13.4788 215.566 -2.19991 -0.0105401 0.0160138 -0.419981 0.90733 +VERTEX_SE3:QUAT 1351 -11.2724 212.01 -2.26626 -0.011176 0.0185874 -0.544357 0.838573 +VERTEX_SE3:QUAT 1352 -10.2854 208.028 -2.29528 -0.0124923 0.00893457 -0.670732 0.741541 +VERTEX_SE3:QUAT 1353 -10.6082 203.875 -2.24779 -0.01314 0.00634735 -0.780565 0.624904 +VERTEX_SE3:QUAT 1354 -12.237 199.839 -2.18732 -0.00864056 0.00272651 -0.854048 0.520115 +VERTEX_SE3:QUAT 1355 -14.649 196.156 -2.11716 -0.00614456 0.000465802 -0.88511 0.46534 +VERTEX_SE3:QUAT 1356 -17.028 192.895 -2.06 -0.00920618 0.000130821 -0.886319 0.462984 +VERTEX_SE3:QUAT 1357 -19.3769 189.605 -1.97376 -0.0106858 0.00392254 -0.883507 0.468279 +VERTEX_SE3:QUAT 1358 -21.8687 186.014 -1.88948 -0.00634621 0.00916107 -0.88034 0.474212 +VERTEX_SE3:QUAT 1359 -24.1326 182.699 -1.8706 -0.0041055 0.0101629 -0.87685 0.480638 +VERTEX_SE3:QUAT 1360 -26.5347 179.01 -1.85524 -0.00488496 0.0100506 -0.873064 0.487478 +VERTEX_SE3:QUAT 1361 -28.8855 175.371 -1.8323 -0.00688228 0.0125803 -0.878979 0.476645 +VERTEX_SE3:QUAT 1362 -31.2816 172.183 -1.79879 -0.0098368 0.00938711 -0.907351 0.420154 +VERTEX_SE3:QUAT 1363 -34.4208 169.356 -1.75804 -0.00593031 0.0103539 -0.958289 0.285553 +VERTEX_SE3:QUAT 1364 -38.4109 167.813 -1.69599 -0.00918273 0.011478 -0.996746 0.0792542 +VERTEX_SE3:QUAT 1365 -42.3813 167.989 -1.60696 0.00719579 -0.00626563 0.993682 0.111824 +VERTEX_SE3:QUAT 1366 -46.1025 169.533 -1.51794 -0.00660829 0.00333177 0.967528 0.252657 +VERTEX_SE3:QUAT 1367 -49.5819 171.91 -1.63901 -0.019904 0.00811182 0.953451 0.30078 +VERTEX_SE3:QUAT 1368 -52.7759 174.271 -1.79947 -0.0206942 0.00872437 0.952104 0.304949 +VERTEX_SE3:QUAT 1369 -55.9906 176.688 -1.95023 -0.0242237 0.00732056 0.95124 0.307411 +VERTEX_SE3:QUAT 1370 -59.4164 179.286 -2.15037 -0.0242175 0.00938934 0.950811 0.30868 +VERTEX_SE3:QUAT 1371 -62.6372 181.732 -2.33929 -0.0233528 0.0088327 0.951037 0.308067 +VERTEX_SE3:QUAT 1372 -65.8906 184.194 -2.52109 -0.0256805 0.00914451 0.951221 0.307304 +VERTEX_SE3:QUAT 1373 -69.3404 186.81 -2.73497 -0.025609 0.0107684 0.951501 0.30639 +VERTEX_SE3:QUAT 1374 -72.6678 189.323 -2.93567 -0.0284745 0.0107385 0.951531 0.306042 +VERTEX_SE3:QUAT 1375 -76.2003 191.973 -3.16416 -0.029683 0.0101426 0.95134 0.306544 +VERTEX_SE3:QUAT 1376 -79.5778 194.518 -3.39476 -0.0282968 0.0111406 0.951476 0.306217 +VERTEX_SE3:QUAT 1377 -82.7801 196.911 -3.60973 -0.0284271 0.00981964 0.951991 0.304647 +VERTEX_SE3:QUAT 1378 -86.1739 199.429 -3.83836 -0.0294352 0.01032 0.952883 0.30173 +VERTEX_SE3:QUAT 1379 -89.4234 201.805 -4.06545 -0.0275878 0.0122121 0.95342 0.300135 +VERTEX_SE3:QUAT 1380 -92.7839 204.303 -4.31971 -0.0346688 0.012136 0.946952 0.31927 +VERTEX_SE3:QUAT 1381 -95.7877 206.983 -4.58404 -0.0317157 0.0121828 0.920957 0.38818 +VERTEX_SE3:QUAT 1382 -98.2656 210.498 -4.85911 -0.0273597 0.00302218 0.842229 0.538417 +VERTEX_SE3:QUAT 1383 -99.0733 214.72 -5.0238 -0.0203503 0.0004371 0.700611 0.713253 +VERTEX_SE3:QUAT 1384 -98.1678 218.74 -5.13074 -0.018433 -0.00249452 0.557641 0.829874 +VERTEX_SE3:QUAT 1385 -96.0061 222.306 -5.17229 -0.00802973 -0.0037638 0.457112 0.889365 +VERTEX_SE3:QUAT 1386 -93.3912 225.579 -5.16533 -0.00794259 -0.00273819 0.435364 0.900215 +VERTEX_SE3:QUAT 1387 -90.8159 228.767 -5.16345 -0.00929275 -0.000357692 0.448972 0.893497 +VERTEX_SE3:QUAT 1388 -88.3534 232.016 -5.17768 -0.0101994 -0.000733326 0.456902 0.889458 +VERTEX_SE3:QUAT 1389 -85.7894 235.421 -5.23215 -0.0143621 0.00709536 0.45397 0.890873 +VERTEX_SE3:QUAT 1390 -83.2829 238.761 -5.33208 -0.0205503 0.00942972 0.457077 0.889139 +VERTEX_SE3:QUAT 1391 -80.7619 242.153 -5.45773 -0.0165425 0.0105062 0.463761 0.885744 +VERTEX_SE3:QUAT 1392 -78.3526 245.561 -5.57263 -0.0189159 0.0092145 0.466123 0.884469 +VERTEX_SE3:QUAT 1393 -75.7232 249.025 -5.68891 -0.0245433 0.00261713 0.416067 0.908999 +VERTEX_SE3:QUAT 1394 -72.6213 251.813 -5.7619 -0.0279877 0.000232045 0.287576 0.957349 +VERTEX_SE3:QUAT 1395 -68.7418 253.311 -5.78294 -0.0259843 -0.00378882 0.0775281 0.996644 +VERTEX_SE3:QUAT 1396 -64.4535 252.986 -5.74136 -0.0239124 -0.00853783 -0.133426 0.990733 +VERTEX_SE3:QUAT 1397 -60.7862 251.331 -5.62574 -0.01193 0.00971807 -0.246965 0.968902 +VERTEX_SE3:QUAT 1398 -57.0767 248.891 -5.67238 -0.0111463 0.00291473 -0.298577 0.954316 +VERTEX_SE3:QUAT 1399 -53.7022 246.348 -5.65015 -0.00727809 -0.001462 -0.308307 0.951258 +VERTEX_SE3:QUAT 1400 -50.2107 243.705 -5.61089 -0.00723805 -0.00459642 -0.308964 0.951035 +VERTEX_SE3:QUAT 1401 -47.0113 241.27 -5.55527 -0.00695967 -0.00307862 -0.308876 0.951072 +VERTEX_SE3:QUAT 1402 -43.7554 238.791 -5.50283 -0.0059327 -0.00206364 -0.308726 0.95113 +VERTEX_SE3:QUAT 1403 -40.1678 236.093 -5.45032 -0.0119216 -0.00494368 -0.311179 0.950264 +VERTEX_SE3:QUAT 1404 -36.7887 233.471 -5.36441 -0.0132435 -0.00537705 -0.319173 0.947589 +VERTEX_SE3:QUAT 1405 -33.3942 230.716 -5.30504 -0.00977952 0.00775809 -0.32821 0.944522 +VERTEX_SE3:QUAT 1406 -30.0374 227.902 -5.31936 -0.00796516 0.00461381 -0.330599 0.943726 +VERTEX_SE3:QUAT 1407 -26.8321 225.186 -5.31356 -0.00321072 0.00326895 -0.331569 0.94342 +VERTEX_SE3:QUAT 1408 -23.7567 222.632 -5.2995 -0.00577503 0.000296222 -0.32782 0.944722 +VERTEX_SE3:QUAT 1409 -20.4499 219.946 -5.26544 -0.00495344 0.00216864 -0.321272 0.946972 +VERTEX_SE3:QUAT 1410 -17.0733 217.264 -5.22964 -0.0128101 -0.0069598 -0.323861 0.945992 +VERTEX_SE3:QUAT 1411 -13.967 214.548 -5.10081 -0.0086138 0.012386 -0.373706 0.927424 +VERTEX_SE3:QUAT 1412 -11.2289 211.269 -5.1539 -0.0101254 0.0115247 -0.467792 0.883706 +VERTEX_SE3:QUAT 1413 -9.50682 207.382 -5.17448 -0.00966731 0.00857293 -0.628089 0.778034 +VERTEX_SE3:QUAT 1414 -9.62202 203.389 -5.14134 -0.00677463 0.00535799 -0.787113 0.616748 +VERTEX_SE3:QUAT 1415 -11.4024 199.617 -5.10978 -0.0127423 -0.00146641 -0.876442 0.481336 +VERTEX_SE3:QUAT 1416 -13.8796 196.332 -4.99065 -0.00789862 -0.00211586 -0.896925 0.442108 +VERTEX_SE3:QUAT 1417 -16.6433 193.001 -4.90093 -0.00942791 -0.00388842 -0.903517 0.428432 +VERTEX_SE3:QUAT 1418 -19.2243 189.949 -4.79606 -0.0103567 -0.00329267 -0.900083 0.435583 +VERTEX_SE3:QUAT 1419 -21.826 186.724 -4.69529 -0.00611899 -0.000299385 -0.894638 0.446749 +VERTEX_SE3:QUAT 1420 -24.4307 183.362 -4.65067 -0.00263513 0.00331221 -0.892603 0.450824 +VERTEX_SE3:QUAT 1421 -27.1019 179.935 -4.6346 -0.00259077 0.00486081 -0.895167 0.445697 +VERTEX_SE3:QUAT 1422 -29.689 176.688 -4.61326 -0.00267363 0.00319352 -0.895105 0.445836 +VERTEX_SE3:QUAT 1423 -32.3966 173.218 -4.59006 -0.00559752 0.00678515 -0.894396 0.447189 +VERTEX_SE3:QUAT 1424 -34.9598 169.944 -4.55817 -0.0137012 0.00499122 -0.893805 0.448219 +VERTEX_SE3:QUAT 1425 -37.4287 166.774 -4.46949 -0.0106281 0.00518758 -0.892744 0.450409 +VERTEX_SE3:QUAT 1426 -39.993 163.437 -4.38401 -0.00977166 0.00297756 -0.891225 0.453446 +VERTEX_SE3:QUAT 1427 -42.4355 160.205 -4.29336 -0.0106729 0.00340214 -0.889642 0.456521 +VERTEX_SE3:QUAT 1428 -44.9969 156.783 -4.19763 -0.00285254 0.00564313 -0.888702 0.458442 +VERTEX_SE3:QUAT 1429 -47.393 153.554 -4.18864 -0.00131872 0.00556265 -0.887976 0.459854 +VERTEX_SE3:QUAT 1430 -49.7812 150.31 -4.19733 -0.00157086 0.00607797 -0.887183 0.461375 +VERTEX_SE3:QUAT 1431 -52.2514 146.957 -4.19035 -0.00144247 0.00366539 -0.888297 0.459253 +VERTEX_SE3:QUAT 1432 -54.8283 143.511 -4.18001 -0.00613159 0.0141604 -0.90032 0.434955 +VERTEX_SE3:QUAT 1433 -57.8125 140.348 -4.15302 -0.0121954 0.0084408 -0.93732 0.348155 +VERTEX_SE3:QUAT 1434 -61.4237 138.216 -4.06868 -0.0108714 0.00434109 -0.983151 0.18242 +VERTEX_SE3:QUAT 1435 -65.5604 137.453 -3.99344 -0.00763569 0.00937209 -0.999918 0.00429456 +VERTEX_SE3:QUAT 1436 -69.4996 138.132 -3.93175 0.00198603 -0.00325068 0.987609 0.156887 +VERTEX_SE3:QUAT 1437 -73.2386 140.036 -3.94604 -0.0105968 0.00348353 0.96124 0.275489 +VERTEX_SE3:QUAT 1438 -76.4882 142.391 -4.01878 -0.0031479 0.00591782 0.95097 0.309209 +VERTEX_SE3:QUAT 1439 -79.7676 144.961 -4.04574 -0.00359917 0.0052911 0.947655 0.319232 +VERTEX_SE3:QUAT 1440 -83.0471 147.603 -4.0651 -0.000588002 0.00685917 0.94672 0.321985 +VERTEX_SE3:QUAT 1441 -86.31 150.201 -4.06762 -0.00207804 0.00262665 0.947575 0.319517 +VERTEX_SE3:QUAT 1442 -89.6068 152.799 -4.06358 0.000790641 -0.000511979 0.948055 0.318106 +VERTEX_SE3:QUAT 1443 -92.8409 155.354 -4.04565 -0.00911809 0.00385525 0.948297 0.31723 +VERTEX_SE3:QUAT 1444 -96.1115 157.936 -4.12842 -0.012788 0.00633166 0.948446 0.316616 +VERTEX_SE3:QUAT 1445 -99.4482 160.574 -4.23645 -0.00701106 0.0080797 0.948944 0.315262 +VERTEX_SE3:QUAT 1446 -102.845 163.247 -4.29631 -0.00421811 0.0103183 0.949546 0.313429 +VERTEX_SE3:QUAT 1447 -106.256 165.882 -4.33933 -0.00265411 0.0109533 0.950406 0.310807 +VERTEX_SE3:QUAT 1448 -109.556 168.39 -4.36731 -0.00276924 0.0116759 0.951985 0.305908 +VERTEX_SE3:QUAT 1449 -113.031 170.919 -4.39717 -0.00156395 0.00189152 0.95375 0.300592 +VERTEX_SE3:QUAT 1450 -116.322 173.347 -4.39769 0.00161563 -0.000644816 0.948433 0.316973 +VERTEX_SE3:QUAT 1451 -119.494 176.18 -4.37214 -0.0199722 -0.000266022 0.915822 0.401087 +VERTEX_SE3:QUAT 1452 -121.793 179.794 -4.51749 -0.0179694 -0.000409697 0.830362 0.556935 +VERTEX_SE3:QUAT 1453 -122.592 183.796 -4.61228 -0.0197176 0.00230798 0.712936 0.700949 +VERTEX_SE3:QUAT 1454 -121.807 187.926 -4.72178 -0.0204638 -0.000720629 0.569872 0.821478 +VERTEX_SE3:QUAT 1455 -119.781 191.513 -4.76614 -0.0107842 -0.00411439 0.473113 0.880926 +VERTEX_SE3:QUAT 1456 -117.253 194.903 -4.74918 -0.0108396 -0.00387825 0.449109 0.893403 +VERTEX_SE3:QUAT 1457 -114.643 198.255 -4.74838 -0.0111204 -0.00365678 0.449658 0.893124 +VERTEX_SE3:QUAT 1458 -112.143 201.527 -4.74302 -0.0106516 -0.00352284 0.453745 0.891061 +VERTEX_SE3:QUAT 1459 -109.63 204.828 -4.76385 -0.0130822 0.00544393 0.456694 0.889511 +VERTEX_SE3:QUAT 1460 -107.041 208.279 -4.85978 -0.012902 0.00382284 0.458979 0.888345 +VERTEX_SE3:QUAT 1461 -104.446 211.799 -4.94848 -0.0120487 0.00310266 0.460295 0.887679 +VERTEX_SE3:QUAT 1462 -101.868 215.291 -5.0218 -0.0145312 0.00506563 0.457475 0.889089 +VERTEX_SE3:QUAT 1463 -99.4736 218.518 -5.09559 -0.0187888 0.00121053 0.457825 0.888843 +VERTEX_SE3:QUAT 1464 -96.7943 222.094 -5.14414 -0.0120129 -0.000831172 0.460903 0.887369 +VERTEX_SE3:QUAT 1465 -94.3567 225.448 -5.16125 -0.0111977 -0.00271899 0.464909 0.885283 +VERTEX_SE3:QUAT 1466 -91.864 228.951 -5.16839 -0.0129517 -0.000410317 0.466964 0.884181 +VERTEX_SE3:QUAT 1467 -89.4667 232.186 -5.19949 -0.0123531 -0.00266103 0.440829 0.897502 +VERTEX_SE3:QUAT 1468 -86.584 235.362 -5.23584 -0.020023 0.00518332 0.365659 0.930519 +VERTEX_SE3:QUAT 1469 -83.1282 237.636 -5.31073 -0.0244312 0.00573877 0.186212 0.982189 +VERTEX_SE3:QUAT 1470 -79.1829 238.246 -5.34949 -0.0274977 -0.000374251 -0.0301278 0.999168 +VERTEX_SE3:QUAT 1471 -74.9657 237.158 -5.29089 -0.0213132 -0.00428571 -0.187963 0.981935 +VERTEX_SE3:QUAT 1472 -71.3598 235.27 -5.23007 -0.0129817 0.00382874 -0.256253 0.966515 +VERTEX_SE3:QUAT 1473 -67.9175 233.063 -5.21716 -0.0139036 0.00367335 -0.282109 0.959275 +VERTEX_SE3:QUAT 1474 -64.4315 230.648 -5.19983 -0.0188893 0.00191311 -0.294861 0.955352 +VERTEX_SE3:QUAT 1475 -61.1949 228.314 -5.15707 -0.0186762 0.0023874 -0.298321 0.95428 +VERTEX_SE3:QUAT 1476 -57.9399 225.922 -5.1123 -0.0201722 0.00154968 -0.305025 0.952129 +VERTEX_SE3:QUAT 1477 -54.6621 223.448 -5.05832 -0.0211484 -0.00150736 -0.30819 0.951088 +VERTEX_SE3:QUAT 1478 -51.4659 220.998 -4.97047 -0.0165958 -0.00541166 -0.307705 0.951322 +VERTEX_SE3:QUAT 1479 -48.24 218.571 -4.87089 -0.0170265 -0.00493242 -0.306644 0.951659 +VERTEX_SE3:QUAT 1480 -44.9919 216.125 -4.80014 -0.0125305 0.00473637 -0.306596 0.951745 +VERTEX_SE3:QUAT 1481 -41.4732 213.477 -4.79386 -0.0107398 0.00599443 -0.305328 0.952168 +VERTEX_SE3:QUAT 1482 -38.0182 210.893 -4.78931 -0.0143644 0.00820386 -0.309911 0.950622 +VERTEX_SE3:QUAT 1483 -34.7685 208.395 -4.77956 -0.0165427 0.00614418 -0.314051 0.949242 +VERTEX_SE3:QUAT 1484 -31.5145 205.848 -4.75741 -0.0182675 0.00199263 -0.321938 0.946583 +VERTEX_SE3:QUAT 1485 -28.4062 203.27 -4.68425 -0.0167848 -0.00478492 -0.339444 0.940464 +VERTEX_SE3:QUAT 1486 -25.2938 200.425 -4.56369 -0.0129893 0.00893269 -0.373053 0.927676 +VERTEX_SE3:QUAT 1487 -22.6199 197.4 -4.58871 -0.0125409 0.0116793 -0.452677 0.89151 +VERTEX_SE3:QUAT 1488 -20.793 193.802 -4.58592 -0.0187245 0.00567205 -0.601685 0.798494 +VERTEX_SE3:QUAT 1489 -20.6457 189.615 -4.49926 -0.0147688 -0.00080353 -0.777665 0.628505 +VERTEX_SE3:QUAT 1490 -22.2274 185.927 -4.3902 -0.00569784 0.00132241 -0.867506 0.497392 +VERTEX_SE3:QUAT 1491 -24.5502 182.568 -4.3608 -0.00353814 0.00152706 -0.887743 0.460324 +VERTEX_SE3:QUAT 1492 -26.9701 179.345 -4.33825 -0.00346984 0.00354114 -0.892568 0.450886 +VERTEX_SE3:QUAT 1493 -29.5174 176.098 -4.30081 -0.00337517 0.00123972 -0.895144 0.445763 +VERTEX_SE3:QUAT 1494 -32.149 172.771 -4.26773 -0.00413229 0.00380948 -0.896758 0.442485 +VERTEX_SE3:QUAT 1495 -34.6629 169.649 -4.22921 -0.0133166 0.000276321 -0.89735 0.441119 +VERTEX_SE3:QUAT 1496 -37.2015 166.452 -4.13023 -0.0111138 0.00176873 -0.894125 0.447676 +VERTEX_SE3:QUAT 1497 -39.8814 162.962 -4.0269 -0.0103593 -0.000350033 -0.890099 0.45565 +VERTEX_SE3:QUAT 1498 -42.2872 159.733 -3.92573 -0.0118202 0.00149299 -0.890063 0.455683 +VERTEX_SE3:QUAT 1499 -44.9011 156.529 -3.82122 -0.00433288 0.00621918 -0.918494 0.395363 +VERTEX_SE3:QUAT 1500 -48.1176 154.057 -3.79711 -0.00340386 0.00818457 -0.971321 0.237605 +VERTEX_SE3:QUAT 1501 -52.119 152.884 -3.78127 -0.00257212 0.00651967 -0.998457 0.0550824 +VERTEX_SE3:QUAT 1502 -56.2385 153.232 -3.74669 0.00793854 -0.0027493 0.992964 0.11812 +VERTEX_SE3:QUAT 1503 -60.2967 154.917 -3.69311 -0.0101186 0.00784739 0.971163 0.238074 +VERTEX_SE3:QUAT 1504 -63.9262 157.272 -3.79147 -0.00543713 0.00231595 0.953743 0.300564 +VERTEX_SE3:QUAT 1505 -67.2701 159.8 -3.83483 -0.00123587 0.000117524 0.950769 0.309898 +VERTEX_SE3:QUAT 1506 -70.8075 162.512 -3.83976 -0.00192298 0.00231922 0.95032 0.31126 +VERTEX_SE3:QUAT 1507 -74.3336 165.235 -3.84796 -0.000861008 0.00209824 0.949917 0.312495 +VERTEX_SE3:QUAT 1508 -77.8008 167.916 -3.84398 -0.000379333 0.00247138 0.949619 0.313397 +VERTEX_SE3:QUAT 1509 -81.3181 170.648 -3.83795 -0.0110761 0.00411201 0.948859 0.31548 +VERTEX_SE3:QUAT 1510 -84.7293 173.319 -3.93991 -0.0141073 0.00507171 0.948897 0.31523 +VERTEX_SE3:QUAT 1511 -87.8802 175.765 -4.04703 -0.00944994 0.00124008 0.949328 0.314144 +VERTEX_SE3:QUAT 1512 -91.0725 178.221 -4.10531 -0.00927589 -0.000901068 0.950006 0.312093 +VERTEX_SE3:QUAT 1513 -94.6381 180.919 -4.15845 -0.00942808 -0.00269608 0.951134 0.308624 +VERTEX_SE3:QUAT 1514 -98.0658 183.5 -4.19705 -0.00813273 -0.00365856 0.952266 0.305139 +VERTEX_SE3:QUAT 1515 -101.303 185.944 -4.22347 -0.00243551 0.00384925 0.953412 0.301636 +VERTEX_SE3:QUAT 1516 -104.821 188.518 -4.23253 -0.00405994 0.00297974 0.950395 0.311004 +VERTEX_SE3:QUAT 1517 -108.048 191.309 -4.23732 -0.0174062 0.00654651 0.919152 0.393464 +VERTEX_SE3:QUAT 1518 -110.306 194.676 -4.37289 -0.0152882 -0.00231439 0.831199 0.55576 +VERTEX_SE3:QUAT 1519 -111 198.73 -4.44281 -0.012485 -0.00255846 0.692595 0.721214 +VERTEX_SE3:QUAT 1520 -109.87 202.814 -4.47719 -0.0140435 0.00307062 0.536722 0.843637 +VERTEX_SE3:QUAT 1521 -107.846 206.376 -4.54641 -0.0146446 0.00843892 0.522817 0.852277 +VERTEX_SE3:QUAT 1522 -106.263 210.441 -4.66709 -0.0103024 0.0104569 0.666776 0.745114 +VERTEX_SE3:QUAT 1523 -106.891 214.688 -4.77429 -0.00461524 0.00951911 0.852206 0.523099 +VERTEX_SE3:QUAT 1524 -109.412 217.978 -4.90553 -0.0217029 0.0166748 0.931823 0.361879 +VERTEX_SE3:QUAT 1525 -112.475 220.623 -5.08181 -0.0184913 0.0203451 0.945615 0.324125 +VERTEX_SE3:QUAT 1526 -115.614 223.155 -5.24881 -0.0193993 0.0179633 0.948874 0.314547 +VERTEX_SE3:QUAT 1527 -118.903 225.613 -5.44681 -0.015238 0.0195809 0.96298 0.268427 +VERTEX_SE3:QUAT 1528 -122.728 227.301 -5.64647 -0.00949756 0.0254208 0.995108 0.0949925 +VERTEX_SE3:QUAT 1529 -127.076 227.469 -5.70756 -0.0107704 -0.0207758 -0.995932 0.087015 +VERTEX_SE3:QUAT 1530 -131.447 226.044 -5.6467 -0.0055749 -0.0270541 -0.969019 0.245436 +VERTEX_SE3:QUAT 1531 -135.048 223.64 -5.57778 -0.000643431 -0.030382 -0.936687 0.348847 +VERTEX_SE3:QUAT 1532 -138.073 220.728 -5.50802 -0.00387481 -0.0291514 -0.911523 0.410196 +VERTEX_SE3:QUAT 1533 -141.059 217.273 -5.40562 -0.00488286 -0.0262912 -0.899012 0.437107 +VERTEX_SE3:QUAT 1534 -144.147 213.344 -5.2716 -0.00569609 -0.0212976 -0.894583 0.446358 +VERTEX_SE3:QUAT 1535 -146.688 210.112 -5.17917 -0.00680608 -0.0204617 -0.894105 0.447339 +VERTEX_SE3:QUAT 1536 -149.349 206.725 -5.07471 -0.00514601 -0.0210983 -0.893432 0.448674 +VERTEX_SE3:QUAT 1537 -152.127 203.158 -4.98276 -0.00470739 -0.0208604 -0.892453 0.450634 +VERTEX_SE3:QUAT 1538 -154.966 199.474 -4.88613 -0.00414323 -0.01912 -0.891729 0.452148 +VERTEX_SE3:QUAT 1539 -158.075 195.428 -4.79792 -0.0046794 -0.0205951 -0.891086 0.453343 +VERTEX_SE3:QUAT 1540 -161.131 191.429 -4.68749 -0.00234873 -0.0209009 -0.890664 0.454176 +VERTEX_SE3:QUAT 1541 -164.252 187.311 -4.59354 -0.00332942 -0.0185716 -0.89048 0.45463 +VERTEX_SE3:QUAT 1542 -167.451 183.109 -4.48613 0.00159494 -0.0164714 -0.889881 0.455893 +VERTEX_SE3:QUAT 1543 -170.491 179.068 -4.40003 0.00253649 -0.0170516 -0.889345 0.456912 +VERTEX_SE3:QUAT 1544 -173.49 175.047 -4.31672 0.00109951 -0.0148584 -0.888894 0.457871 +VERTEX_SE3:QUAT 1545 -176.524 170.953 -4.2426 -0.000629168 -0.0136476 -0.888164 0.459324 +VERTEX_SE3:QUAT 1546 -179.355 167.122 -4.14667 -0.00263444 -0.0145544 -0.886666 0.462174 +VERTEX_SE3:QUAT 1547 -182.128 163.339 -4.06374 -0.00022863 -0.0150328 -0.884719 0.465883 +VERTEX_SE3:QUAT 1548 -184.839 159.543 -3.97797 0.00382346 -0.0176491 -0.881759 0.471354 +VERTEX_SE3:QUAT 1549 -187.445 155.778 -3.90858 0.0018729 -0.017567 -0.878765 0.476928 +VERTEX_SE3:QUAT 1550 -189.99 151.984 -3.82477 0.00509947 -0.0196258 -0.873663 0.486109 +VERTEX_SE3:QUAT 1551 -192.339 148.245 -3.7825 -0.000104407 -0.0167922 -0.867769 0.496683 +VERTEX_SE3:QUAT 1552 -194.729 144.265 -3.68911 -0.000985299 -0.0200676 -0.860746 0.508638 +VERTEX_SE3:QUAT 1553 -196.804 140.564 -3.59671 0.00839185 -0.015365 -0.853056 0.521525 +VERTEX_SE3:QUAT 1554 -198.87 136.605 -3.58181 0.00608057 -0.0188349 -0.845313 0.533905 +VERTEX_SE3:QUAT 1555 -200.773 132.669 -3.52574 0.00600111 -0.0206516 -0.837295 0.546328 +VERTEX_SE3:QUAT 1556 -202.623 128.56 -3.45572 0.00652917 -0.0212275 -0.829179 0.558542 +VERTEX_SE3:QUAT 1557 -204.319 124.457 -3.38756 0.0049236 -0.0228287 -0.820891 0.570608 +VERTEX_SE3:QUAT 1558 -205.871 120.358 -3.2955 0.00783821 -0.0205684 -0.812896 0.581993 +VERTEX_SE3:QUAT 1559 -207.293 116.31 -3.23485 0.005664 -0.0223885 -0.804912 0.592945 +VERTEX_SE3:QUAT 1560 -208.614 112.234 -3.15303 0.00878868 -0.0223476 -0.797089 0.603384 +VERTEX_SE3:QUAT 1561 -209.782 108.218 -3.09159 0.00888959 -0.0205429 -0.789161 0.613778 +VERTEX_SE3:QUAT 1562 -210.865 104.14 -3.02974 0.00790315 -0.019476 -0.781223 0.623898 +VERTEX_SE3:QUAT 1563 -211.853 99.9959 -2.96462 0.00743473 -0.0204838 -0.77274 0.634348 +VERTEX_SE3:QUAT 1564 -212.711 95.9557 -2.89213 0.00935712 -0.0215548 -0.764223 0.644524 +VERTEX_SE3:QUAT 1565 -213.453 91.9258 -2.82332 0.0124474 -0.0224829 -0.755397 0.654763 +VERTEX_SE3:QUAT 1566 -214.069 87.9694 -2.77291 0.013864 -0.0229483 -0.746131 0.665259 +VERTEX_SE3:QUAT 1567 -214.575 83.965 -2.72139 0.0126003 -0.0240947 -0.735902 0.676542 +VERTEX_SE3:QUAT 1568 -215.007 79.017 -2.63922 0.00980725 -0.0214188 -0.722114 0.691373 +VERTEX_SE3:QUAT 1569 -215.25 73.9781 -2.55005 0.00994119 -0.0229816 -0.709819 0.703939 +VERTEX_SE3:QUAT 1570 -215.326 69.279 -2.44378 0.0102394 -0.0205772 -0.699886 0.713885 +VERTEX_SE3:QUAT 1571 -215.293 64.5996 -2.34936 0.0122901 -0.0193178 -0.691572 0.721945 +VERTEX_SE3:QUAT 1572 -215.155 60.1147 -2.27397 0.012356 -0.0194694 -0.681421 0.731528 +VERTEX_SE3:QUAT 1573 -214.887 55.7635 -2.18753 0.0190928 -0.0137004 -0.669223 0.74269 +VERTEX_SE3:QUAT 1574 -214.389 51.0697 -2.17835 0.0045873 -0.0166031 -0.655998 0.754566 +VERTEX_SE3:QUAT 1575 -213.793 46.6409 -2.0519 0.0116412 -0.0132381 -0.642065 0.766448 +VERTEX_SE3:QUAT 1576 -213.114 42.5583 -1.99427 0.0131053 -0.0160018 -0.629793 0.776487 +VERTEX_SE3:QUAT 1577 -212.246 38.2277 -1.92362 0.0129027 -0.0117921 -0.621576 0.783159 +VERTEX_SE3:QUAT 1578 -211.379 34.2383 -1.87965 0.011122 -0.00941633 -0.613929 0.789227 +VERTEX_SE3:QUAT 1579 -210.408 30.2616 -1.85221 0.000656956 -0.0176546 -0.604791 0.796188 +VERTEX_SE3:QUAT 1580 -209.242 26.0695 -1.76237 0.00381694 -0.0154056 -0.572185 0.819971 +VERTEX_SE3:QUAT 1581 -207.483 22.2146 -1.66762 -0.000715438 -0.015429 -0.478456 0.877976 +VERTEX_SE3:QUAT 1582 -204.777 18.8525 -1.56143 -0.00521333 -0.0126463 -0.362682 0.931813 +VERTEX_SE3:QUAT 1583 -201.449 16.3785 -1.48095 -0.00452867 -0.0159862 -0.244092 0.96961 +VERTEX_SE3:QUAT 1584 -197.33 14.7334 -1.34745 0.00139838 -0.00525577 -0.11305 0.993574 +VERTEX_SE3:QUAT 1585 -193.218 14.1893 -1.31318 0.00288501 -0.00161266 0.00229663 0.999992 +VERTEX_SE3:QUAT 1586 -188.813 14.5568 -1.28355 0.00525756 0.0120816 0.0994089 0.994959 +VERTEX_SE3:QUAT 1587 -184.294 15.7086 -1.33846 0.00630048 -0.0013454 0.154024 0.988046 +VERTEX_SE3:QUAT 1588 -180.236 16.9286 -1.33083 0.0104032 -0.00104639 0.159785 0.987096 +VERTEX_SE3:QUAT 1589 -176.205 18.1744 -1.2928 0.00846107 -1.65284e-05 0.15981 0.987111 +VERTEX_SE3:QUAT 1590 -172.114 19.4303 -1.27201 0.00892149 -0.00284589 0.16042 0.987004 +VERTEX_SE3:QUAT 1591 -167.901 20.7364 -1.2307 0.0087723 -0.00293213 0.16223 0.98671 +VERTEX_SE3:QUAT 1592 -163.565 22.0961 -1.18253 0.0109274 -0.000879486 0.165036 0.986227 +VERTEX_SE3:QUAT 1593 -159.722 23.3394 -1.14741 0.0121353 -0.000243959 0.168959 0.985548 +VERTEX_SE3:QUAT 1594 -155.503 24.749 -1.13006 0.00927161 -0.00106242 0.172855 0.984903 +VERTEX_SE3:QUAT 1595 -150.875 26.3336 -1.10278 0.0091813 -0.00161417 0.17468 0.984581 +VERTEX_SE3:QUAT 1596 -146.19 27.9542 -1.05812 0.00637673 0.000530926 0.175389 0.984478 +VERTEX_SE3:QUAT 1597 -142.365 29.251 -1.0375 0.00683708 -1.09056e-06 0.175319 0.984488 +VERTEX_SE3:QUAT 1598 -137.631 30.8707 -1.01032 0.0075243 0.00161044 0.17578 0.984399 +VERTEX_SE3:QUAT 1599 -132.918 32.4807 -0.993798 0.00732691 0.000915541 0.175468 0.984457 +VERTEX_SE3:QUAT 1600 -128.064 34.1305 -0.965597 0.0107301 0.00177508 0.174345 0.984625 +VERTEX_SE3:QUAT 1601 -123.399 35.6989 -0.942879 0.00951692 -2.5271e-05 0.173301 0.984823 +VERTEX_SE3:QUAT 1602 -118.702 37.2684 -0.907507 0.00913766 0.000526725 0.172566 0.984955 +VERTEX_SE3:QUAT 1603 -114.051 38.832 -0.883258 0.0101284 0.000525029 0.171581 0.985118 +VERTEX_SE3:QUAT 1604 -109.369 40.3574 -0.839953 0.0149144 -0.00440051 0.166457 0.985926 +VERTEX_SE3:QUAT 1605 -104.747 41.8282 -0.772635 0.00907878 -0.00558618 0.160076 0.987047 +VERTEX_SE3:QUAT 1606 -100.279 43.1723 -0.677068 0.00695069 -0.00468887 0.154804 0.98791 +VERTEX_SE3:QUAT 1607 -95.614 44.5191 -0.596108 0.00874489 -0.00547195 0.15023 0.988597 +VERTEX_SE3:QUAT 1608 -91.2862 45.7419 -0.516727 0.00464984 -0.00666542 0.145206 0.989368 +VERTEX_SE3:QUAT 1609 -86.7456 46.9226 -0.447726 0.0119131 -0.00574717 0.136358 0.990571 +VERTEX_SE3:QUAT 1610 -82.4333 47.9619 -0.360585 0.0112528 -0.00569659 0.123588 0.992253 +VERTEX_SE3:QUAT 1611 -78.2006 48.8703 -0.275999 0.00902199 -0.00478994 0.111076 0.993759 +VERTEX_SE3:QUAT 1612 -73.8985 49.6941 -0.207809 0.00832286 -0.00443442 0.0995206 0.994991 +VERTEX_SE3:QUAT 1613 -69.6266 50.3823 -0.161291 0.00829958 -0.00594473 0.0840229 0.996412 +VERTEX_SE3:QUAT 1614 -65.3516 50.9371 -0.101144 0.00744383 -0.00482167 0.0687732 0.997593 +VERTEX_SE3:QUAT 1615 -61.0754 51.3652 -0.0441144 0.00577375 -0.00385894 0.0536426 0.998536 +VERTEX_SE3:QUAT 1616 -56.7261 51.6749 0.00752449 0.00531086 -0.00464929 0.0408495 0.99914 +VERTEX_SE3:QUAT 1617 -52.3547 51.8507 0.0537473 0.00657416 -0.00435168 0.0231051 0.999702 +VERTEX_SE3:QUAT 1618 -48.0229 51.8684 0.0900054 0.0069108 -0.00324304 0.00474555 0.99996 +VERTEX_SE3:QUAT 1619 -43.631 51.7166 0.129104 0.00926488 -0.00408327 -0.0114404 0.999883 +VERTEX_SE3:QUAT 1620 -39.297 51.4361 0.17065 0.0100598 -0.00503335 -0.0272262 0.999566 +VERTEX_SE3:QUAT 1621 -34.9091 51.0349 0.208191 0.00950725 -0.002445 -0.0407724 0.99912 +VERTEX_SE3:QUAT 1622 -30.4605 50.5352 0.237 0.00436221 -0.00155858 -0.0534311 0.998561 +VERTEX_SE3:QUAT 1623 -26.0759 49.9105 0.249744 0.000641198 0.0026755 -0.0649413 0.997885 +VERTEX_SE3:QUAT 1624 -21.7098 49.2127 0.225563 0.00123259 0.00531061 -0.0713548 0.997436 +VERTEX_SE3:QUAT 1625 -17.2585 48.4109 0.176671 0.00549036 0.00100882 -0.0799272 0.996785 +VERTEX_SE3:QUAT 1626 -12.9627 47.5483 0.155385 0.00630824 0.00674437 -0.0951022 0.995425 +VERTEX_SE3:QUAT 1627 -8.57301 46.502 0.101579 0.00764921 0.00924361 -0.112149 0.993619 +VERTEX_SE3:QUAT 1628 -4.25961 45.3609 0.038459 0.00765811 0.00640152 -0.124662 0.992149 +VERTEX_SE3:QUAT 1629 0.0180213 44.0892 -0.0189575 0.00813383 0.00910085 -0.14211 0.989776 +VERTEX_SE3:QUAT 1630 4.36591 42.6048 -0.0968432 0.00828692 0.0104263 -0.163596 0.986437 +VERTEX_SE3:QUAT 1631 8.2922 41.0317 -0.172674 0.00802198 0.0102918 -0.191535 0.981399 +VERTEX_SE3:QUAT 1632 12.2443 39.1981 -0.253711 0.00499985 0.00953239 -0.214426 0.976681 +VERTEX_SE3:QUAT 1633 16.0815 37.2608 -0.335786 0.00557757 0.0102062 -0.22502 0.974285 +VERTEX_SE3:QUAT 1634 19.9392 35.2345 -0.418014 0.00775678 0.0125551 -0.231168 0.972802 +VERTEX_SE3:QUAT 1635 23.649 33.2475 -0.519992 0.0089025 0.0106553 -0.236617 0.971504 +VERTEX_SE3:QUAT 1636 27.327 31.2481 -0.599894 0.0051237 0.0150452 -0.241924 0.970165 +VERTEX_SE3:QUAT 1637 31.4233 28.9117 -0.714794 0.00700268 0.0144633 -0.247157 0.968842 +VERTEX_SE3:QUAT 1638 35.0436 26.7972 -0.820767 0.0103051 0.0155405 -0.252421 0.967438 +VERTEX_SE3:QUAT 1639 38.4922 24.7058 -0.929492 0.00829119 0.0164432 -0.275765 0.961049 +VERTEX_SE3:QUAT 1640 41.8487 22.0344 -1.06499 0.00651747 0.018577 -0.390001 0.920604 +VERTEX_SE3:QUAT 1641 44.0721 18.3334 -1.24009 -0.0206229 0.0167393 -0.595869 0.802642 +VERTEX_SE3:QUAT 1642 44.2327 13.884 -1.20509 -0.0131207 0.0139602 -0.754619 0.655884 +VERTEX_SE3:QUAT 1643 43.1665 9.99352 -1.1901 -0.0116975 0.0135197 -0.81371 0.580997 +VERTEX_SE3:QUAT 1644 41.5278 6.20596 -1.16508 -0.0150905 0.0171894 -0.850719 0.525122 +VERTEX_SE3:QUAT 1645 39.3153 2.86235 -1.11504 -0.0106853 0.0158088 -0.901816 0.4317 +VERTEX_SE3:QUAT 1646 36.2042 0.115695 -1.06458 -0.0127974 0.0140013 -0.958751 0.283615 +VERTEX_SE3:QUAT 1647 32.1959 -1.60762 -0.955713 -0.0139357 0.0075456 -0.988994 0.147101 +VERTEX_SE3:QUAT 1648 27.853 -2.34349 -0.826732 -0.00963816 0.00304902 -0.998276 0.0578221 +VERTEX_SE3:QUAT 1649 23.4887 -2.67173 -0.72624 -0.0136168 0.00152797 -0.999036 0.0417169 +VERTEX_SE3:QUAT 1650 19.246 -2.94131 -0.605647 -0.00961223 0.00384626 -0.999231 0.0378055 +VERTEX_SE3:QUAT 1651 15.166 -3.15808 -0.512005 -0.00291507 -0.00111882 -0.999019 0.0441847 +VERTEX_SE3:QUAT 1652 11.0605 -3.50661 -0.47249 -0.00189466 0.00647752 -0.998864 0.0471673 +VERTEX_SE3:QUAT 1653 6.89966 -3.66003 -0.407699 -0.00477142 -0.000842579 0.999516 0.0307264 +VERTEX_SE3:QUAT 1654 3.03777 -2.46556 -0.42474 0.00743576 -0.00438125 0.959414 0.28187 +VERTEX_SE3:QUAT 1655 0.24119 0.770358 -0.368958 0.00211114 0.00310235 0.853356 0.521315 +VERTEX_SE3:QUAT 1656 -0.926586 4.58673 -0.371826 -0.00152823 0.000959441 0.765922 0.642931 +VERTEX_SE3:QUAT 1657 -1.16209 8.68382 -0.387923 0.00165807 0.00310673 0.704296 0.709898 +VERTEX_SE3:QUAT 1658 -0.888073 12.8799 -0.360451 0.00107498 0.00690652 0.685761 0.727794 +VERTEX_SE3:QUAT 1659 -0.574597 17.1106 -0.377747 0.00538606 0.0107384 0.681793 0.731447 +VERTEX_SE3:QUAT 1660 -0.0944743 21.306 -0.408636 0.00745758 0.0145585 0.712572 0.701408 +EDGE_SE3:QUAT 0 1 4.15448 -0.0665288 0.000389663 -0.0107791 0.00867285 -0.00190021 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 -0.000375887 0.0691425 3.9997 -8.5017e-05 4.00118 +EDGE_SE3:QUAT 1 2 4.15971 -0.0912353 0.0567356 0.00272799 -0.000777724 0.00363979 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.64848e-06 -0.00634076 4 -1.1571e-05 3.99996 +EDGE_SE3:QUAT 2 3 4.28985 -0.0247738 -0.00423717 -0.00251893 -0.015912 0.0148755 0.99976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.004 0.000250029 -0.126914 3.999 -0.00096047 4.00314 +EDGE_SE3:QUAT 3 4 4.19815 -0.0648981 -0.0412507 0.00809376 0.00983641 0.0096526 0.999872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00125 0.000335718 0.0777606 3.99963 0.000392584 4.00114 +EDGE_SE3:QUAT 4 5 4.16073 -0.0800714 -0.00683181 -0.00610256 -0.000133946 -0.00562439 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 4.94074e-06 -0.00148332 4 4.55294e-06 3.99987 +EDGE_SE3:QUAT 5 6 4.53017 -0.123911 -0.0250554 0.00437116 0.00742819 -0.00548444 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 0.000123487 0.0597205 3.99978 -0.000158288 4.00077 +EDGE_SE3:QUAT 6 7 4.08996 -0.114357 0.0084345 -0.00224706 0.00488201 -0.00220577 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -4.50641e-05 0.0389992 3.99991 -4.42828e-05 4.00036 +EDGE_SE3:QUAT 7 8 4.4972 -0.0368689 0.0305298 0.00169669 -0.00214664 0.0230253 0.999731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.24311e-05 -0.0176283 3.99998 -0.000204509 3.99796 +EDGE_SE3:QUAT 8 9 4.34366 0.175615 0.0227239 0.00757089 0.0022955 0.0869368 0.996182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 3.34958e-05 0.0102964 4 0.000330501 3.96979 +EDGE_SE3:QUAT 9 10 4.15685 0.48636 -0.00411743 -0.00149517 -0.00318863 0.13577 0.990734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 4.33404e-05 -0.0224014 3.99997 -0.00144986 3.92639 +EDGE_SE3:QUAT 10 11 4.29022 0.480612 0.0108215 0.00212114 0.00229424 0.139963 0.990152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.59367e-05 0.0143012 3.99999 0.000905188 3.92169 +EDGE_SE3:QUAT 11 12 4.09147 0.453422 0.0338667 -0.00128138 0.00294306 0.122954 0.992407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.18564e-05 0.024885 3.99996 0.00155739 3.93968 +EDGE_SE3:QUAT 12 13 4.33741 0.243695 0.0306209 -0.00425808 -0.000525027 0.0591607 0.998239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 3.85731e-07 -0.00116223 4 -4.35887e-06 3.986 +EDGE_SE3:QUAT 13 14 4.05604 0.0272498 0.0210505 -0.00563827 -0.00141707 0.0252084 0.999665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 2.64541e-05 -0.00962047 3.99999 -0.000114258 3.99748 +EDGE_SE3:QUAT 14 15 4.04679 0.130947 0.0158262 -0.00521682 0.0051938 0.120486 0.992688 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -3.22058e-05 0.0481234 3.99985 0.00302885 3.94251 +EDGE_SE3:QUAT 15 16 4.23869 0.882735 0.0784195 0.00170297 -0.0264247 0.24305 0.969652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00975 0.00362587 -0.198128 3.99832 -0.0236338 3.77347 +EDGE_SE3:QUAT 16 17 3.96598 0.59573 -0.0345204 0.00829326 0.00803217 0.173305 0.984801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 0.00031337 0.0444787 3.99993 0.00327979 3.88034 +EDGE_SE3:QUAT 17 18 4.20856 0.357531 -0.0286207 0.011349 0.00546783 0.109745 0.99388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000170955 0.0281219 3.99997 0.00125957 3.95201 +EDGE_SE3:QUAT 18 19 4.33681 0.0998401 -0.00860454 0.0033234 -0.00167297 0.039042 0.999231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.25098e-05 -0.0149086 3.99999 -0.000300706 3.99396 +EDGE_SE3:QUAT 19 20 4.26984 -0.057287 -0.0182644 0.000221923 0.00410408 0.013191 0.999905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 8.95979e-06 0.0327909 3.99993 0.000216304 3.99957 +EDGE_SE3:QUAT 20 21 4.62193 -0.0485773 -0.00654039 0.00229106 -0.0065356 0.010666 0.999919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 -4.93342e-05 -0.0525767 3.99983 -0.000278654 4.00024 +EDGE_SE3:QUAT 21 22 4.04814 -0.0552791 -0.0119384 -0.00270598 0.00665023 0.0103284 0.999921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -6.15448e-05 0.0535365 3.99982 0.000274263 4.00029 +EDGE_SE3:QUAT 22 23 4.25516 -0.0214021 0.00270387 -0.00333093 0.000288424 0.016711 0.999855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.2737e-06 0.00297421 4 2.66986e-05 3.99889 +EDGE_SE3:QUAT 23 24 4.6127 -0.0179721 -0.00861072 0.000764114 0.00202416 0.0177286 0.99984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 7.81566e-06 0.0160234 3.99998 0.000141613 3.99881 +EDGE_SE3:QUAT 24 25 4.44503 -0.0523622 0.00056694 0.00402409 -0.000426651 0.0163772 0.999858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -8.88539e-06 -0.00420245 4 -3.65423e-05 3.99893 +EDGE_SE3:QUAT 25 26 4.75183 -0.042221 -0.00748827 -0.000308966 0.000967011 0.0139246 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -8.89633e-07 0.00778549 4 5.43131e-05 3.99924 +EDGE_SE3:QUAT 26 27 4.85765 -0.0429295 -0.0199257 -0.00111682 0.00217664 0.0139792 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -8.24433e-06 0.0175956 3.99998 0.000123288 3.9993 +EDGE_SE3:QUAT 27 28 4.10041 -0.0312675 -0.00691899 -0.000140687 0.000464248 0.015987 0.999872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.80059e-07 0.00373955 4 2.99596e-05 3.99898 +EDGE_SE3:QUAT 28 29 5.00969 0.000382475 0.00542828 -0.00366627 0.00337265 0.0187558 0.999812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -4.60856e-05 0.0277926 3.99995 0.000262154 3.99879 +EDGE_SE3:QUAT 29 30 4.94706 -0.0217959 0.00791578 0.000142706 0.000985997 0.0175872 0.999845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.67318e-07 0.00785423 4 6.89719e-05 3.99878 +EDGE_SE3:QUAT 30 31 4.73799 -0.0415418 0.0255281 -0.00110489 0.00307645 0.0129453 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -1.07485e-05 0.0247778 3.99996 0.000160497 3.99948 +EDGE_SE3:QUAT 31 32 4.88374 -0.0562155 0.0259943 -0.00120536 0.000921553 0.0115099 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.333e-06 0.00753743 4 4.3669e-05 3.99948 +EDGE_SE3:QUAT 32 33 4.69559 -0.0409947 0.0173165 0.00127778 0.00263806 0.0146134 0.999889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.56879e-05 0.0208742 3.99997 0.00015218 3.99925 +EDGE_SE3:QUAT 33 34 4.56333 -0.0407636 0.0212397 -0.00153168 0.00234998 0.0144129 0.999892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.27116e-05 0.0190592 3.99998 0.000137772 3.99926 +EDGE_SE3:QUAT 34 35 4.50349 -0.0548443 0.0300326 0.00201897 0.00357501 0.0145462 0.999886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 3.27649e-05 0.0282397 3.99995 0.000205148 3.99935 +EDGE_SE3:QUAT 35 36 4.28599 -0.044706 0.0235666 0.00413789 -0.000792013 0.0155269 0.999871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.49491e-05 -0.00710453 4 -5.70703e-05 3.99905 +EDGE_SE3:QUAT 36 37 4.25164 -0.0317075 0.0386368 -0.00193966 0.00507797 0.0159102 0.999859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -2.98885e-05 0.0409821 3.99989 0.000325831 3.99941 +EDGE_SE3:QUAT 37 38 4.71327 -0.000657242 0.0282638 -0.000961562 -3.09584e-05 0.0188769 0.999821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.05763e-08 -2.97706e-05 4 4.04715e-07 3.99857 +EDGE_SE3:QUAT 38 39 4.24504 -0.017373 0.0326678 -0.0050487 1.63877e-05 0.0180465 0.999824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -4.00359e-06 0.00122411 4 1.43319e-05 3.9987 +EDGE_SE3:QUAT 39 40 4.46205 -0.034552 0.0735074 0.00769102 0.00695617 0.018952 0.999767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 0.000225922 0.0538741 3.99982 0.000513621 3.99929 +EDGE_SE3:QUAT 40 41 4.1489 -0.0232755 0.0507316 -0.00788702 -0.00310241 0.00830393 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 9.5554e-05 -0.0240293 3.99996 -0.000100417 3.99987 +EDGE_SE3:QUAT 41 42 4.11651 -0.112282 0.0496252 0.00140666 -0.00412833 -0.0266807 0.999634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -3.34484e-05 -0.032543 3.99993 0.000432614 3.99742 +EDGE_SE3:QUAT 42 43 4.09543 -0.648383 0.00545628 -0.000985727 0.00211564 -0.165469 0.986212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -2.05484e-05 0.0143133 3.99999 -0.00111081 3.89053 +EDGE_SE3:QUAT 43 44 3.89524 -0.930021 0.00469593 -0.0194178 -0.035218 -0.26953 0.962152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.02284 -0.00664426 -0.313055 3.99532 0.0435146 3.73377 +EDGE_SE3:QUAT 44 45 4.17817 -0.768652 -0.112173 -0.00761817 0.0463888 -0.140994 0.988894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.03005 -0.00802803 0.34954 3.99348 -0.024963 3.95077 +EDGE_SE3:QUAT 45 46 4.24162 -0.278879 0.00201523 -0.000660178 -0.00235592 -0.0474503 0.998871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -1.32929e-07 -0.0191595 3.99998 0.000456967 3.99109 +EDGE_SE3:QUAT 46 47 4.41282 -0.249472 0.00326565 -0.00430876 0.012678 -0.0464464 0.998831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00236 -0.000383181 0.0987466 3.99941 -0.00229177 3.99381 +EDGE_SE3:QUAT 47 48 4.05714 -0.323211 0.00243731 0.0137064 -0.0229835 -0.0540379 0.99818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00684 -0.00181151 -0.174418 3.9982 0.00480973 3.99591 +EDGE_SE3:QUAT 48 49 4.21745 -0.290623 0.0395959 0.00157447 -0.026667 -0.0624296 0.997692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01113 -0.00121935 -0.211423 3.99729 0.00664962 3.99555 +EDGE_SE3:QUAT 49 50 4.07607 -0.388421 8.56352e-07 -0.0022891 0.0228351 -0.076732 0.996788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.008 -0.00114 0.179278 3.99807 -0.00689539 3.98447 +EDGE_SE3:QUAT 50 51 4.26435 -0.373646 -0.0431778 0.00209348 0.0282777 -0.0756148 0.996734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0128 -0.00122109 0.226811 3.99688 -0.0086066 3.98995 +EDGE_SE3:QUAT 51 52 4.36278 -0.63955 -0.00464176 -0.00216072 0.00543334 -0.133635 0.991013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -0.000120808 0.0388864 3.99992 -0.00249686 3.92894 +EDGE_SE3:QUAT 52 53 4.02476 -0.583398 0.00284604 0.00507033 -0.00251622 -0.098984 0.995073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -3.84171e-05 -0.0138508 3.99999 0.000581694 3.96086 +EDGE_SE3:QUAT 53 54 4.26903 -0.199342 0.00186521 0.00137098 -0.000630898 -0.0132039 0.999912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.37786e-06 -0.00482865 4 3.14099e-05 3.99931 +EDGE_SE3:QUAT 54 55 4.42495 -0.0204833 0.00231648 0.000286523 0.00246546 0.0149062 0.999886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 4.97981e-06 0.0196663 3.99998 0.000146482 3.99921 +EDGE_SE3:QUAT 55 56 4.40559 -0.00548906 0.00822832 -0.00166584 0.00504874 0.0152353 0.99987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -2.45491e-05 0.0406839 3.9999 0.000309706 3.99949 +EDGE_SE3:QUAT 56 57 4.5839 -0.061808 0.0197524 -0.00179213 -0.00510927 0.00621207 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 4.03489e-05 -0.0407417 3.9999 -0.000127556 4.00026 +EDGE_SE3:QUAT 57 58 4.65638 -0.0804731 0.0105465 0.000389743 0.00128446 0.00523866 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.20267e-06 0.0102508 3.99999 2.68444e-05 3.99992 +EDGE_SE3:QUAT 58 59 4.77963 -0.0616422 0.0156684 -0.00127249 0.00460978 0.00631903 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -2.03146e-05 0.0369752 3.99991 0.000116297 4.00018 +EDGE_SE3:QUAT 59 60 3.99786 -0.047224 0.0263936 -0.0018695 -0.00110115 0.00714873 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.23594e-06 -0.00864818 4 -3.07731e-05 3.99981 +EDGE_SE3:QUAT 60 61 4.64774 -0.0467343 0.00364908 0.000125219 0.000597 0.00784329 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.64829e-07 0.00476378 4 1.8667e-05 3.99976 +EDGE_SE3:QUAT 61 62 4.59935 -0.0506332 0.0375537 -0.00392487 -0.00521191 0.00278327 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 8.33143e-05 -0.0415667 3.99989 -6.03471e-05 4.0004 +EDGE_SE3:QUAT 62 63 4.46799 -0.0763324 0.0356431 -0.00631716 -0.00459327 -0.00373461 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 0.000115367 -0.0370291 3.99991 6.60973e-05 4.00029 +EDGE_SE3:QUAT 63 64 4.33405 -0.0846141 0.013387 0.000484854 8.00934e-05 -0.000557044 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.56295e-07 0.000643988 4 -1.7959e-07 4 +EDGE_SE3:QUAT 64 65 4.54211 -0.070602 0.0256335 0.00051281 -0.00278516 0.00435012 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -4.9112e-06 -0.022308 3.99997 -4.84485e-05 4.00005 +EDGE_SE3:QUAT 65 66 4.72575 -0.0630238 0.016584 0.0008923 -0.00150739 0.00671247 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.0532e-06 -0.0121303 3.99999 -4.07435e-05 3.99986 +EDGE_SE3:QUAT 66 67 4.619 -0.0730671 0.00792645 0.00172291 5.52855e-05 0.00628202 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.32071e-07 0.000312379 4 8.45247e-07 3.99984 +EDGE_SE3:QUAT 67 68 4.58578 -0.0512691 0.0282897 -0.000207872 0.00321433 0.00397294 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -1.68859e-06 0.0257249 3.99996 5.10617e-05 4.0001 +EDGE_SE3:QUAT 68 69 4.0716 -0.139603 0.0346497 0.00101606 -0.00121712 -0.00942861 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.19707e-06 -0.00962078 3.99999 4.52087e-05 3.99967 +EDGE_SE3:QUAT 69 70 4.28332 -0.0402705 0.0440563 0.00108073 -0.00237421 0.0146309 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -8.38713e-06 -0.0191777 3.99998 -0.000140601 3.99924 +EDGE_SE3:QUAT 70 71 4.42309 0.0973701 0.0363667 -0.00245218 0.00183342 0.0519175 0.998647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.55104e-05 0.0161332 3.99998 0.000431289 3.98928 +EDGE_SE3:QUAT 71 72 4.34897 0.357554 0.0319799 0.000773158 -0.00172367 0.132329 0.991204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 4.68761e-06 -0.0146423 3.99999 -0.000987751 3.93001 +EDGE_SE3:QUAT 72 73 4.04108 0.665525 0.0221723 -0.00231806 -0.00391894 0.203146 0.979138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 7.5483e-05 -0.0239358 3.99998 -0.00217319 3.83507 +EDGE_SE3:QUAT 73 74 4.21969 0.754546 -0.00396633 0.0110184 -0.0179339 0.201008 0.979364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00598 0.000976385 -0.160949 3.99852 -0.0167267 3.84485 +EDGE_SE3:QUAT 74 75 4.21298 0.548362 0.0499571 -0.0025905 -0.00922049 0.154105 0.988008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00107 0.000353721 -0.0664512 3.99977 -0.0049372 3.90611 +EDGE_SE3:QUAT 75 76 4.05832 0.204423 -0.040508 0.000667243 0.030166 0.0271129 0.999177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01454 0.00067443 0.24161 3.99639 0.00331906 4.0116 +EDGE_SE3:QUAT 76 77 4.09226 -0.594625 0.0415699 -0.00288934 -0.0157442 -0.204046 0.978831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00388 -0.00104632 -0.125156 3.9992 0.0127504 3.83737 +EDGE_SE3:QUAT 77 78 4.05445 -1.38211 -0.00840915 0.00152977 -7.42901e-05 -0.32973 0.944074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.50833e-06 0.00511411 4 -0.00117946 3.56512 +EDGE_SE3:QUAT 78 79 4.05595 -1.17911 -0.0221212 0.0045047 0.0076922 -0.226408 0.973992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -0.000232534 0.0687053 3.99974 -0.00805147 3.79614 +EDGE_SE3:QUAT 79 80 4.17738 -0.338371 -0.0160067 -0.000351947 0.00672344 -0.0425835 0.99907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 -5.52108e-05 0.05347 3.99982 -0.00113707 3.99346 +EDGE_SE3:QUAT 80 81 3.99904 -0.0814193 -0.00348701 -0.000224802 -0.00120106 0.00189154 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.14468e-06 -0.00960335 3.99999 -9.08887e-06 4.00001 +EDGE_SE3:QUAT 81 82 4.17605 -0.0563225 0.00777269 -0.000656942 0.00150307 0.00890704 0.999959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.49268e-06 0.0120934 3.99999 5.39257e-05 3.99972 +EDGE_SE3:QUAT 82 83 4.19871 -0.0351079 0.0153087 -0.00250025 0.000583715 0.0156154 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.46737e-06 0.00513641 4 4.12948e-05 3.99903 +EDGE_SE3:QUAT 83 84 4.10913 0.00499386 0.0323789 0.00184373 -0.00626869 0.045323 0.998951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 -3.36991e-06 -0.0510036 3.99984 -0.00116092 3.99243 +EDGE_SE3:QUAT 84 85 4.324 0.524971 0.0137421 0.00324559 -0.00297899 0.170522 0.985344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 6.77077e-07 -0.0293138 3.99994 -0.00265713 3.8839 +EDGE_SE3:QUAT 85 86 4.08861 0.736112 0.014077 0.00309873 -0.00303202 0.21923 0.975664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 2.08222e-05 -0.0304209 3.99994 -0.00356532 3.80798 +EDGE_SE3:QUAT 86 87 4.16829 0.831732 -0.00558391 0.00444193 -0.00259854 0.222103 0.97501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -6.18538e-06 -0.0307199 3.99994 -0.00378912 3.80292 +EDGE_SE3:QUAT 87 88 4.12649 0.552609 0.0134976 -0.00600456 0.0141882 0.129292 0.991487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00345 0.000319563 0.119976 3.99913 0.00788048 3.93673 +EDGE_SE3:QUAT 88 89 4.01864 0.0335201 -0.00633305 -0.00453327 0.00500361 0.0155899 0.999856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -8.3604e-05 0.0408648 3.99989 0.000317973 3.99945 +EDGE_SE3:QUAT 89 90 4.28424 -0.195672 0.0247062 -0.00253002 -0.0101146 -0.0298915 0.999499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00164 2.92625e-05 -0.081745 3.99958 0.00122073 3.9981 +EDGE_SE3:QUAT 90 91 4.43191 -0.209935 -0.0115107 -0.00143447 0.00183711 -0.0230326 0.999732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.19377e-05 0.014289 3.99999 -0.000163106 3.99793 +EDGE_SE3:QUAT 91 92 4.05329 -0.123974 0.00635004 0.00296087 -0.00186975 -0.00212333 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.21727e-05 -0.0148825 3.99999 1.60204e-05 4.00004 +EDGE_SE3:QUAT 92 93 4.19402 -0.0827696 0.00704784 0.00572478 0.000722096 0.00600222 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 1.50266e-05 0.00536386 4 1.57484e-05 3.99986 +EDGE_SE3:QUAT 93 94 4.22215 -0.0610937 0.017332 0.00303134 -0.00311069 0.00983052 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -3.61042e-05 -0.0252401 3.99996 -0.000123934 3.99977 +EDGE_SE3:QUAT 94 95 4.40271 -0.0266413 -0.00918459 -0.00184311 0.0151821 0.00924648 0.99984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00369 -6.11895e-05 0.121744 3.99907 0.000554273 4.00336 +EDGE_SE3:QUAT 95 96 4.44046 -0.0448038 0.0137955 -0.00381706 -0.00458805 0.00541848 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 7.21429e-05 -0.0364565 3.99992 -0.000100473 4.00021 +EDGE_SE3:QUAT 96 97 4.40647 -0.0773661 0.0180209 -0.00331702 -0.00276709 0.00204412 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 3.69103e-05 -0.0220554 3.99997 -2.31219e-05 4.0001 +EDGE_SE3:QUAT 97 98 4.25153 -0.0863218 0.010117 0.00245084 0.00148736 0.00230868 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.45918e-05 0.0118309 3.99999 1.37599e-05 4.00001 +EDGE_SE3:QUAT 98 99 4.31587 -0.0764418 0.00894097 -0.00148724 0.00157754 0.00189251 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -9.30493e-06 0.0126541 3.99999 1.18957e-05 4.00003 +EDGE_SE3:QUAT 99 100 4.44086 -0.0985895 0.0295186 0.00244814 -0.00181385 0.00103209 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.77305e-05 -0.0145411 3.99999 -7.31541e-06 4.00005 +EDGE_SE3:QUAT 100 101 4.00354 -0.0737645 0.0160394 0.00549296 -0.00757291 0.0141232 0.999856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -0.000149958 -0.0615061 3.99976 -0.000428999 4.00015 +EDGE_SE3:QUAT 101 102 4.28908 0.0098973 0.00641285 0.00622558 0.00545478 0.0469928 0.998861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 0.00015008 0.039989 3.99991 0.000915102 3.99157 +EDGE_SE3:QUAT 102 103 4.36897 0.355859 -0.0293634 0.00033505 0.011503 0.124279 0.992181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.002 0.00039536 0.0894439 3.99954 0.0055116 3.94022 +EDGE_SE3:QUAT 103 104 4.13705 0.502294 0.0059195 0.00276748 -0.00185241 0.154127 0.988045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -9.19855e-06 -0.0193321 3.99997 -0.00160716 3.90507 +EDGE_SE3:QUAT 104 105 4.16518 0.579522 0.00973185 -0.00441048 0.00334709 0.172007 0.98508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -1.14211e-05 0.034523 3.99992 0.00319381 3.88195 +EDGE_SE3:QUAT 105 106 4.05627 0.590029 0.0426526 -0.00710639 -0.00312729 0.180166 0.983606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 2.17117e-05 -0.0087771 4 -0.000292466 3.87017 +EDGE_SE3:QUAT 106 107 4.12005 0.668184 0.0190195 -0.00303233 -0.00844252 0.234018 0.972191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 0.000365412 -0.0538696 3.9999 -0.00575381 3.78166 +EDGE_SE3:QUAT 107 108 4.09573 0.946036 -0.0251498 0.00834169 -0.00294028 0.267188 0.963604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -4.81517e-05 -0.0465248 3.99984 -0.00728091 3.71497 +EDGE_SE3:QUAT 108 109 4.02437 0.846778 -0.0217617 0.000881363 0.00228009 0.221425 0.975174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.61442e-05 0.0146506 3.99999 0.0014845 3.80394 +EDGE_SE3:QUAT 109 110 4.24155 0.454787 -0.00591316 -0.000739944 0.00773455 0.105163 0.994425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 0.000128638 0.0617926 3.99977 0.00324838 3.95672 +EDGE_SE3:QUAT 110 111 4.33443 0.107257 -0.0110079 -7.21036e-05 0.00652845 0.0378415 0.999262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 3.67718e-05 0.0521559 3.99983 0.000986696 3.99495 +EDGE_SE3:QUAT 111 112 4.29721 -0.0305293 0.0147498 -0.0053702 -0.00238004 0.00933514 0.999939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.01706e-05 -0.0184358 3.99998 -8.58086e-05 3.99974 +EDGE_SE3:QUAT 112 113 4.61598 -0.0789154 0.0117452 0.000244887 -0.00163625 2.22617e-06 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.60271e-06 -0.0130902 3.99999 1.16511e-09 4.00004 +EDGE_SE3:QUAT 113 114 4.05789 -0.0883887 0.00830758 -0.00228935 -0.000159161 0.000934643 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.41885e-06 -0.0012476 4 -5.80378e-07 4 +EDGE_SE3:QUAT 114 115 4.11933 -0.0884276 0.0140516 0.000553461 -0.000750708 0.00085375 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.65249e-06 -0.00601134 4 -2.55941e-06 4.00001 +EDGE_SE3:QUAT 115 116 4.27268 -0.12712 0.010531 0.00544979 -0.00587882 -0.0017623 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 -0.000129244 -0.0469186 3.99986 4.58264e-05 4.00054 +EDGE_SE3:QUAT 116 117 4.09029 -0.0909554 -0.000219786 0.0010578 -0.00130254 -0.00288838 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.60247e-06 -0.0103836 3.99999 1.50212e-05 3.99999 +EDGE_SE3:QUAT 117 118 4.20158 -0.100788 0.018774 -0.00139623 0.0155461 -0.00482121 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00386 -0.000115005 0.124388 3.99904 -0.000308643 4.00377 +EDGE_SE3:QUAT 118 119 3.99909 -0.130577 0.0241141 0.00183988 -0.000436102 -0.004103 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.11624e-06 -0.00339812 4 6.9173e-06 3.99994 +EDGE_SE3:QUAT 119 120 4.53978 -0.107182 0.0200143 -0.00177575 -0.00123559 -0.00446043 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.72287e-06 -0.00997951 3.99999 2.22612e-05 3.99995 +EDGE_SE3:QUAT 120 121 4.40804 -0.0748034 0.0299176 -0.00213086 0.000147327 0.00452523 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.41731e-06 0.00129428 4 3.01441e-06 3.99992 +EDGE_SE3:QUAT 121 122 4.36479 -0.0605895 0.0434027 -0.00174133 -0.000405836 0.00627566 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.69758e-06 -0.00311535 4 -9.64453e-06 3.99984 +EDGE_SE3:QUAT 122 123 4.01308 -0.108595 0.0417628 0.00602136 -0.00914532 -0.00367217 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 -0.000226769 -0.0729129 3.99967 0.000145848 4.00127 +EDGE_SE3:QUAT 123 124 4.30636 -0.0893241 0.0381803 -0.00235949 0.00872351 -0.0108417 0.9999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 -0.000101584 0.0694865 3.9997 -0.00038068 4.00074 +EDGE_SE3:QUAT 124 125 4.11816 -0.252067 -0.0143824 0.00320932 0.00973351 -0.0759144 0.997062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00156 -5.11114e-05 0.0801359 3.9996 -0.00306566 3.97855 +EDGE_SE3:QUAT 125 126 4.02908 -0.691592 0.0324877 -0.00602487 -0.00609543 -0.197198 0.980326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 -5.69235e-05 -0.0598448 3.99978 0.00626807 3.84535 +EDGE_SE3:QUAT 126 127 3.9495 -1.1429 -0.0093269 0.00368409 0.00140501 -0.273583 0.96184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 6.56235e-06 0.0214938 3.99997 -0.00342885 3.70072 +EDGE_SE3:QUAT 80 126 5.22787 5.20821 0.0606868 0.00137218 0.0122792 -0.863955 0.503418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000156739 0.0196754 4.00055 0.0168034 1.01404 +EDGE_SE3:QUAT 81 126 1.25508 5.29496 0.065863 0.000439433 0.0131788 -0.864815 0.501917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -5.25389e-05 0.0156142 4.00043 0.0213032 1.00803 +EDGE_SE3:QUAT 82 126 -2.8225 5.3953 0.0511467 0.00232861 0.0131238 -0.869145 0.494377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 -0.000263257 0.024735 4.00079 0.0163676 0.978029 +EDGE_SE3:QUAT 127 128 3.8578 -0.930713 -0.00947043 0.00426395 0.00867911 -0.19382 0.98099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00134 -0.000240612 0.0752495 3.99968 -0.00748027 3.85115 +EDGE_SE3:QUAT 79 127 6.67214 1.79226 -0.0218011 -0.00495896 0.0108061 -0.978463 0.206079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.07282e-05 -0.0203041 3.99954 0.0465298 0.170542 +EDGE_SE3:QUAT 80 127 2.27734 2.31976 0.0245935 0.00105623 0.00979586 -0.968872 0.247366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000136428 0.00578161 3.99992 0.0313581 0.245038 +EDGE_SE3:QUAT 81 127 -1.68976 2.42906 0.0253084 0.000108476 0.0104858 -0.969287 0.245708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000159274 0.00171701 3.99977 0.0355477 0.241832 +EDGE_SE3:QUAT 82 127 -5.80128 2.58455 0.00401478 0.00211916 0.0103575 -0.971433 0.237077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.00014358 0.0102654 4.00004 0.0319334 0.225128 +EDGE_SE3:QUAT 128 129 3.9419 -0.343251 -0.00914902 0.000856198 0.00356396 -0.0482103 0.99883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -2.59998e-06 0.0289082 3.99995 -0.000699845 3.99091 +EDGE_SE3:QUAT 78 128 7.00167 -1.41057 -0.0436913 0.00374043 -0.0112217 0.976619 0.214654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 -0.000156134 -0.0168477 4.00026 0.0336785 0.184686 +EDGE_SE3:QUAT 79 128 2.73281 1.07837 0.00361272 0.00234473 0.00762765 -0.999894 0.0121442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.54152e-05 0.00938191 3.99987 0.0302717 0.000841064 +EDGE_SE3:QUAT 80 128 -1.53799 1.29742 0.0106032 0.00893076 0.00756199 -0.998409 0.0551654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000177191 0.0358956 4.00122 0.0261003 0.0126669 +EDGE_SE3:QUAT 81 128 -5.54293 1.39654 0.0144087 0.00778303 0.00825674 -0.998539 0.0528326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.00019785 0.0312727 4.00086 0.0295262 0.011629 +EDGE_SE3:QUAT 129 130 4.33573 -0.0517113 -0.0030553 -0.00151414 0.000108947 0.0103647 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.45767e-07 0.00105975 4 5.81648e-06 3.99957 +EDGE_SE3:QUAT 78 129 3.55485 0.556151 0.00208014 0.00104116 -0.00928854 0.965174 0.261441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000119873 -0.00589778 3.99995 0.0289317 0.273646 +EDGE_SE3:QUAT 79 129 -1.19647 1.31664 -0.0199452 -0.00528217 -0.00678075 0.999321 0.0358323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000151197 0.0211683 4.0002 0.0285515 0.00545198 +EDGE_SE3:QUAT 80 129 -5.48634 1.20066 -0.070002 0.0123858 0.00727518 -0.999875 0.00662006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 0.000339346 0.0495462 4.00227 0.028465 0.000991528 +EDGE_SE3:QUAT 130 131 4.18099 -0.0353965 0.0111157 0.000382763 0.000659447 0.0142648 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.13849e-06 0.00520846 4 3.69933e-05 3.99919 +EDGE_SE3:QUAT 77 130 5.67813 0.909943 0.0496981 -0.00301453 -0.0118901 0.830614 0.556713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000162695 -0.000187936 3.99997 0.0242825 1.24005 +EDGE_SE3:QUAT 78 130 -0.138843 2.79596 0.0380955 0.000361079 -0.0109906 0.96779 0.251518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.00017585 -0.00297513 3.99979 0.0364853 0.253411 +EDGE_SE3:QUAT 79 130 -5.47488 1.69612 -0.067767 -0.00582677 -0.00823385 0.999624 0.0254802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000196926 0.023331 4.00021 0.0340736 0.00302353 +EDGE_SE3:QUAT 131 132 4.2709 -0.0538855 0.0140294 -0.00549184 -0.00144399 -0.00246809 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 3.21885e-05 -0.011714 3.99999 1.42417e-05 4.00001 +EDGE_SE3:QUAT 77 131 4.14508 4.76429 0.0969819 -0.00396014 -0.0112245 0.838663 0.544521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000226033 0.00666474 3.99982 0.0274606 1.18638 +EDGE_SE3:QUAT 78 131 -3.75511 4.85971 0.071679 -0.000679154 -0.0107376 0.971319 0.237535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000158107 0.001784 3.99967 0.0382294 0.226083 +EDGE_SE3:QUAT 132 133 4.31671 -0.123828 0.0203312 -0.00203533 -0.00723086 -0.00602987 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 5.15093e-05 -0.0580013 3.99979 0.000172546 4.0007 +EDGE_SE3:QUAT 133 134 4.2103 -0.0885329 -0.00126743 0.00138169 0.00209452 0.00343383 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.18835e-05 0.0166992 3.99998 2.87843e-05 4.00002 +EDGE_SE3:QUAT 134 135 4.03221 -0.0581034 0.0175668 0.00239073 -0.000796903 0.00985176 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.90901e-06 -0.00665687 4 -3.32147e-05 3.99962 +EDGE_SE3:QUAT 135 136 4.13472 -0.0557945 0.0296506 -0.00107044 0.0010169 0.00443401 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.28342e-06 0.00819196 4 1.81769e-05 3.99994 +EDGE_SE3:QUAT 136 137 4.09282 -0.183912 0.0352524 -0.000153709 0.00833945 -0.0524592 0.998588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -9.20453e-05 0.0663598 3.99973 -0.00173885 3.99009 +EDGE_SE3:QUAT 137 138 4.15434 -0.669312 0.0042105 -0.0027959 0.00362546 -0.176565 0.984278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -6.39867e-05 0.0218573 3.99998 -0.00171529 3.87542 +EDGE_SE3:QUAT 138 139 3.93946 -0.876284 -0.00732598 0.000740661 0.00105852 -0.211056 0.977473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -3.47366e-06 0.00972891 3.99999 -0.00107201 3.82184 +EDGE_SE3:QUAT 139 140 3.89608 -0.831649 -0.00848984 0.00537929 -0.00322741 -0.177424 0.984114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -4.20524e-05 -0.0133962 4 0.000813547 3.87412 +EDGE_SE3:QUAT 140 141 4.32204 -0.626954 -0.0277184 0.00567517 0.0196465 -0.107649 0.993979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00642 -0.000585008 0.161953 3.99841 -0.0087807 3.96019 +EDGE_SE3:QUAT 141 142 4.35145 -0.292036 0.00572326 -0.00509497 -0.00655511 -0.0418871 0.999088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 9.54959e-05 -0.0548681 3.99981 0.00116094 3.99373 +EDGE_SE3:QUAT 142 143 4.05872 -0.156943 0.00356411 0.00147626 -0.00400557 -0.0143917 0.999887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -2.88692e-05 -0.0317813 3.99994 0.000228657 3.99942 +EDGE_SE3:QUAT 143 144 4.21816 -0.126224 0.0040113 0.00112701 0.001558 -0.00384397 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 6.83722e-06 0.0125158 3.99999 -2.40229e-05 3.99998 +EDGE_SE3:QUAT 144 145 4.32593 -0.114752 0.0150759 0.00106081 -0.000822726 -0.00411385 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.51989e-06 -0.00652928 4 1.34113e-05 3.99994 +EDGE_SE3:QUAT 145 146 4.37429 -0.117158 0.0208657 0.000160956 -0.00182231 -0.00418174 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.50538e-06 -0.0145702 3.99999 3.04723e-05 3.99998 +EDGE_SE3:QUAT 146 147 4.46036 -0.101429 0.00490908 -0.00207775 0.00940947 -0.00393027 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0014 -8.64978e-05 0.0751988 3.99965 -0.000152255 4.00135 +EDGE_SE3:QUAT 147 148 3.97862 -0.101154 -0.0106658 -4.14336e-05 0.00342911 -0.00273645 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -1.3406e-06 0.0274324 3.99995 -3.75492e-05 4.00016 +EDGE_SE3:QUAT 148 149 4.03981 -0.0945974 0.00280153 -0.00184015 -0.0027566 -0.00255182 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 1.98939e-05 -0.0221094 3.99997 2.78988e-05 4.0001 +EDGE_SE3:QUAT 149 150 4.54166 -0.100116 0.0164807 -0.00240407 -0.00176538 -0.00245503 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.69052e-05 -0.0141938 3.99999 1.72713e-05 4.00003 +EDGE_SE3:QUAT 150 151 4.37441 -0.10503 0.0287874 0.000132449 -0.000768824 -0.00198275 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.35147e-07 -0.00614742 4 6.09524e-06 3.99999 +EDGE_SE3:QUAT 151 152 4.19294 -0.101138 0.0316971 0.000844044 0.000641999 -0.00190458 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.1594e-06 0.00515526 4 -4.90703e-06 3.99999 +EDGE_SE3:QUAT 152 153 4.41481 -0.118774 0.0241092 0.00379318 -0.00484242 -0.00178483 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -7.42899e-05 -0.0386603 3.99991 3.66129e-05 4.00036 +EDGE_SE3:QUAT 153 154 3.99493 -0.0971236 0.0149696 0.00149048 0.000978039 0.0031657 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.84654e-06 0.00776758 4 1.22989e-05 3.99997 +EDGE_SE3:QUAT 154 155 4.06021 -0.0121337 0.0296849 0.00182124 0.00911593 0.0424261 0.999056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00128 0.000147825 0.0718242 3.99968 0.00152051 3.99409 +EDGE_SE3:QUAT 155 156 4.40406 0.428779 0.00619373 0.000619838 -0.0010585 0.149145 0.988815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.72395e-06 -0.00927996 3.99999 -0.000712449 3.91104 +EDGE_SE3:QUAT 156 157 4.32241 0.779478 0.00954674 -0.00387911 0.00177865 0.210422 0.977601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.45958e-05 0.022801 3.99996 0.00270732 3.82302 +EDGE_SE3:QUAT 157 158 4.25003 0.90372 0.00610635 -0.00244454 -0.00277143 0.243531 0.969886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.43946e-05 -0.013367 4 -0.00125485 3.76281 +EDGE_SE3:QUAT 158 159 4.00096 0.792794 0.0171945 0.00214332 -0.00897284 0.231219 0.972858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00127 0.000382643 -0.0718593 3.99975 -0.00830886 3.78744 +EDGE_SE3:QUAT 159 160 4.3746 0.915242 -0.00239632 0.00299018 0.000198504 0.224119 0.974557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.17296e-05 -0.00630267 4 -0.00101089 3.79909 +EDGE_SE3:QUAT 160 161 4.07794 0.590683 0.00187631 0.00218138 0.00136646 0.176821 0.98424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.82235e-06 0.00589086 4 0.000369056 3.87494 +EDGE_SE3:QUAT 161 162 4.30673 0.533264 0.00122795 0.00369748 0.00121968 0.147392 0.989071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.39992e-06 0.00299606 4 5.22693e-05 3.9131 +EDGE_SE3:QUAT 162 163 4.14999 0.399166 -0.0317298 -0.0100243 0.0169491 0.105947 0.994177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00493 7.36696e-05 0.146125 3.99866 0.00787255 3.96043 +EDGE_SE3:QUAT 163 164 4.30319 0.244893 0.00773181 -0.0015845 -0.0060968 0.0662253 0.997785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 9.32706e-05 -0.0472038 3.99987 -0.00154752 3.98301 +EDGE_SE3:QUAT 164 165 4.52162 0.0187197 0.013404 -0.00767873 -0.00174204 0.00438135 0.999959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 5.17386e-05 -0.0135311 3.99999 -2.98815e-05 3.99997 +EDGE_SE3:QUAT 165 166 4.01888 -0.137463 0.0081267 0.00108362 -3.04548e-05 -0.0116191 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.28965e-08 -9.25131e-05 4 2.44785e-07 3.99946 +EDGE_SE3:QUAT 166 167 4.08412 -0.117753 0.00853577 0.000396842 -0.00121112 -0.00914797 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.23043e-06 -0.00964424 3.99999 4.40589e-05 3.99969 +EDGE_SE3:QUAT 167 168 4.31218 -0.145717 0.00609945 0.00361154 -0.00265719 -0.0101949 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -3.8989e-05 -0.0208125 3.99997 0.000105933 3.99969 +EDGE_SE3:QUAT 168 169 4.18264 -0.138124 0.00967293 0.00304618 -0.0042581 -0.00880492 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -5.50091e-05 -0.0337406 3.99993 0.000149397 3.99997 +EDGE_SE3:QUAT 169 170 4.27426 -0.121801 0.0047985 0.00268041 0.00666923 -0.00495275 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 6.65176e-05 0.053519 3.99982 -0.00012985 4.00062 +EDGE_SE3:QUAT 170 171 4.42445 -0.112273 -0.0229485 -0.000717725 0.00994325 -0.00415171 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00158 -3.84163e-05 0.0795356 3.99961 -0.000166952 4.00151 +EDGE_SE3:QUAT 171 172 4.31521 -0.105483 0.0115224 -0.00335476 -0.00546387 -0.00236904 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 7.18582e-05 -0.0438098 3.99988 4.9535e-05 4.00046 +EDGE_SE3:QUAT 172 173 4.35602 -0.0855803 0.0112888 -0.00232335 0.000741741 1.31798e-05 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.89366e-06 0.00593426 4 8.42627e-09 4.00001 +EDGE_SE3:QUAT 173 174 4.27127 -0.0791714 0.0155677 0.00243612 -0.00221223 0.00302223 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.13436e-05 -0.0177861 3.99998 -2.66341e-05 4.00004 +EDGE_SE3:QUAT 174 175 3.99324 -0.0880142 0.0251203 0.000498122 -0.00134085 0.00747223 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.36174e-06 -0.0107706 3.99999 -4.02739e-05 3.99981 +EDGE_SE3:QUAT 175 176 4.36676 0.0679655 0.0199613 0.0067207 -0.00573568 0.060837 0.998109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -0.000119074 -0.0505295 3.99983 -0.00157857 3.98583 +EDGE_SE3:QUAT 176 177 4.31894 0.335937 0.00113558 0.00276963 0.0172843 0.111763 0.993581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00433 0.000931959 0.132128 3.999 0.00730643 3.95439 +EDGE_SE3:QUAT 177 178 4.07939 0.403654 0.00639347 -0.00146184 0.00163886 0.125217 0.992127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.36694e-06 0.0149775 3.99999 0.000976957 3.93734 +EDGE_SE3:QUAT 178 179 4.16618 0.467537 0.0354183 -0.00775244 0.0026513 0.143325 0.989642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -9.50857e-05 0.0337111 3.99991 0.00271588 3.91811 +EDGE_SE3:QUAT 179 180 4.25645 0.553863 0.0368578 -0.00733904 -0.00177194 0.154485 0.987966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -1.5729e-05 -0.000281664 4 0.000341751 3.90453 +EDGE_SE3:QUAT 180 181 4.21443 0.516048 0.041155 0.0022267 -0.0139056 0.143784 0.989509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0031 0.000553528 -0.111678 3.99929 -0.00804313 3.92042 +EDGE_SE3:QUAT 181 182 4.06608 0.121115 -0.00627403 -0.00366955 -0.00219379 0.0371035 0.999302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.17959e-05 -0.0158816 3.99999 -0.000284678 3.99456 +EDGE_SE3:QUAT 182 183 4.17044 -0.00159013 -0.0163155 -0.00156569 -0.000616306 0.0163908 0.999864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.67149e-06 -0.00462055 4 -3.70335e-05 3.99893 +EDGE_SE3:QUAT 183 184 4.06881 -0.0820207 -0.00253457 0.00284598 0.000450066 0.00298275 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.94395e-06 0.00349857 4 5.18024e-06 3.99997 +EDGE_SE3:QUAT 138 183 4.35597 4.87226 0.0825467 0.000877041 0.0177808 -0.976797 0.213427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000446693 0.0051288 3.99933 0.0617245 0.183222 +EDGE_SE3:QUAT 139 183 -1.97437 5.40995 0.0829151 -0.00196397 0.0166069 -0.909688 0.414955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99957 0.000399499 -0.000112938 3.99973 0.0450219 0.689452 +EDGE_SE3:QUAT 184 185 4.32988 -0.110934 -0.00935439 0.00203967 0.00744623 -0.00241925 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00087 5.76529e-05 0.0596398 3.99978 -6.94883e-05 4.00087 +EDGE_SE3:QUAT 137 184 5.87032 2.14876 0.0327678 0.000729301 0.0125605 -0.999102 0.0404676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.58537e-05 0.0029323 3.9994 0.0497973 0.00717371 +EDGE_SE3:QUAT 138 184 0.628997 3.25276 0.0483202 0.00260782 0.0153054 -0.976157 0.216511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000335145 0.0123845 3.99987 0.0498659 0.188213 +EDGE_SE3:QUAT 139 184 -4.7018 2.39273 0.0390368 -9.40099e-05 0.0143084 -0.908477 0.41769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000194875 0.00788044 4.00011 0.034119 0.698308 +EDGE_SE3:QUAT 185 186 4.447 -0.0997732 -0.0161994 -0.00152305 0.00575369 -0.0013852 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 -3.61426e-05 0.0460092 3.99987 -3.30804e-05 4.00052 +EDGE_SE3:QUAT 136 185 5.817 1.55909 0.0321943 -0.000537537 -0.0105211 0.999833 0.0149059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.45384e-06 0.0021508 3.99956 0.0421226 0.00133363 +EDGE_SE3:QUAT 137 185 1.53448 1.91859 0.0194028 0.00851466 0.0109561 -0.999195 0.0376386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000335644 0.0341389 4.00085 0.0411248 0.00638181 +EDGE_SE3:QUAT 138 185 -3.36244 1.51345 -0.0012768 0.0105646 0.0149306 -0.976723 0.213725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 -2.87069e-05 0.0462093 4.00245 0.035803 0.183629 +EDGE_SE3:QUAT 186 187 4.10204 -0.0816774 0.0295261 -0.000697048 0.000699199 0.000869432 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.94267e-06 0.00560087 4 2.42766e-06 4 +EDGE_SE3:QUAT 135 186 5.4842 1.75563 0.0455623 -0.00541301 -0.0113343 0.999846 0.0122699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000240872 0.0216607 3.99992 0.0458554 0.00124526 +EDGE_SE3:QUAT 136 186 1.36682 1.78729 0.0140966 -0.00653134 -0.0122202 0.999766 0.016631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000315091 0.0261413 4.00002 0.0497226 0.00189545 +EDGE_SE3:QUAT 137 186 -2.90259 1.68694 -0.0734179 0.0145694 0.0128266 -0.999164 0.0359815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99905 0.000598333 0.0583978 4.00305 0.047006 0.00658518 +EDGE_SE3:QUAT 138 186 -7.43312 -0.238055 -0.13846 0.0162078 0.0179707 -0.976896 0.212341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99831 -0.000423517 0.0704103 4.00554 0.0376771 0.182056 +EDGE_SE3:QUAT 187 188 4.00208 -0.0808921 0.0251608 -0.00241495 -0.000788214 -0.00063072 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.63394e-06 -0.00632395 4 1.96008e-06 4.00001 +EDGE_SE3:QUAT 134 187 5.36877 1.91941 0.0652766 -0.00657976 -0.014385 0.999873 0.00176674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000377561 0.0263268 3.99986 0.0576403 0.00101633 +EDGE_SE3:QUAT 135 187 1.38147 1.94016 0.0331192 -0.00595052 -0.0118796 0.999845 0.0115556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000278983 0.0238115 3.99996 0.0480581 0.00125333 +EDGE_SE3:QUAT 136 187 -2.71778 2.01543 -0.0126272 -0.00741626 -0.0128876 0.999762 0.0159951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000380759 0.029683 4.00014 0.0524767 0.00193223 +EDGE_SE3:QUAT 137 187 -6.98133 1.47893 -0.170473 0.0152428 0.0134689 -0.999118 0.0367484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99896 0.000654604 0.0611028 4.00335 0.049281 0.00694405 +EDGE_SE3:QUAT 188 189 4.04877 -0.0857172 0.0250998 -0.00445072 -0.000797855 0.00190882 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.39295e-05 -0.00628068 4 -6.02821e-06 4 +EDGE_SE3:QUAT 133 188 5.54556 1.93177 0.0490983 0.00366173 0.0184164 -0.999823 0.00154399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000273294 0.0146544 3.99886 0.0736128 0.00141829 +EDGE_SE3:QUAT 134 188 1.3571 2.00909 0.0474 -0.00577287 -0.0168528 0.999839 0.00195921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000386205 0.0231011 3.99939 0.0675038 0.00128807 +EDGE_SE3:QUAT 135 188 -2.62037 2.11182 0.0103604 -0.00526487 -0.0141746 0.99981 0.0123321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000286158 0.0210701 3.9996 0.0571984 0.00153741 +EDGE_SE3:QUAT 136 188 -6.70836 2.22484 -0.0355735 -0.00673268 -0.0154308 0.999721 0.0165376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000400291 0.0269504 3.99969 0.0625781 0.00225486 +EDGE_SE3:QUAT 189 190 4.02823 0.00655227 0.01581 0.00632442 -0.00812579 0.0624384 0.997996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00104 -0.000114358 -0.069368 3.99969 -0.00220143 3.98561 +EDGE_SE3:QUAT 132 189 5.83456 1.86226 0.0844157 -0.0100733 -0.0205191 0.999736 0.00245973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.00082486 0.0403172 3.99991 0.0823013 0.00212369 +EDGE_SE3:QUAT 133 189 1.50431 2.00199 0.049153 0.00258027 0.0225865 -0.999736 0.00333542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000245937 0.0103294 3.99808 0.0902551 0.00210864 +EDGE_SE3:QUAT 134 189 -2.67643 2.10869 0.0318584 -0.00501061 -0.0212278 0.999762 0.000570064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000423508 0.0200557 3.9986 0.0849265 0.00190553 +EDGE_SE3:QUAT 135 189 -6.64704 2.29972 0.0122877 -0.0041782 -0.0188731 0.999761 0.0102589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000289811 0.0167237 3.99882 0.0758085 0.00192817 +EDGE_SE3:QUAT 190 191 3.98809 0.560678 0.0120702 0.00514475 -0.00356909 0.19613 0.980558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -8.67569e-06 -0.0387216 3.9999 -0.00413546 3.8465 +EDGE_SE3:QUAT 131 190 6.09873 1.80095 0.0343759 0.00424745 0.00820659 -0.998283 0.057844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000137826 0.0170887 4.00012 0.030596 0.0136919 +EDGE_SE3:QUAT 132 190 1.80415 1.86536 0.0299579 0.00298654 0.0134766 -0.998104 0.0599899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000224738 0.0120374 3.99955 0.0519937 0.01511 +EDGE_SE3:QUAT 133 190 -2.51239 1.95551 0.0543367 -0.0042501 0.0160079 -0.997691 0.0658678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000149149 -0.017079 3.99908 0.0655621 0.0185068 +EDGE_SE3:QUAT 134 190 -6.67554 2.09951 0.0203804 -0.00197105 0.0145612 -0.997948 0.0623137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.57485e-06 -0.0079028 3.99915 0.0586526 0.0164111 +EDGE_SE3:QUAT 191 192 3.98444 0.685806 0.00523448 0.00809189 -0.00463917 0.216429 0.976254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -3.05894e-05 -0.0549025 3.9998 -0.00659523 3.81338 +EDGE_SE3:QUAT 77 191 2.49343 6.49363 0.0997551 0.0100536 -0.00340179 -0.31559 0.948836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000133051 0.0122956 3.99996 -0.0041627 3.60161 +EDGE_SE3:QUAT 130 191 6.36675 0.813692 0.011448 0.00180971 0.00240782 -0.963969 0.265998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.06314e-05 0.00832797 4.00008 0.004392 0.283045 +EDGE_SE3:QUAT 131 191 2.20245 0.787334 0.00248544 0.00258472 0.00180701 -0.967666 0.252215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.01826e-05 0.0115093 4.00013 0.001221 0.254485 +EDGE_SE3:QUAT 132 191 -2.07746 0.838287 0.00241443 0.00245434 0.00733268 -0.967055 0.254452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 4.8196e-05 0.0116899 4.00016 0.0200212 0.259133 +EDGE_SE3:QUAT 133 191 -6.38472 0.881757 0.0735094 -0.00385057 0.0110837 -0.965512 0.260093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000100316 -0.0153239 3.99948 0.0444831 0.271183 +EDGE_SE3:QUAT 192 193 4.05163 0.683026 -0.0158946 0.00550519 -0.0126061 0.183592 0.982906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00278 0.000486521 -0.107717 3.99934 -0.0100937 3.86808 +EDGE_SE3:QUAT 78 192 -2.12365 5.95307 0.0857962 0.0166378 -0.00632245 0.231108 0.972765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 -0.000272288 -0.091102 3.9994 -0.0121057 3.7884 +EDGE_SE3:QUAT 130 192 3.28409 -1.82421 -0.00760517 0.000183228 -0.00692846 -0.883593 0.468205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 2.81632e-05 -0.00475727 4.00005 -0.0142881 0.876961 +EDGE_SE3:QUAT 131 192 -0.94757 -1.74181 -0.0197992 0.000770978 -0.00766403 -0.890206 0.455493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 6.67795e-05 -0.00190971 4 -0.0181935 0.83003 +EDGE_SE3:QUAT 132 192 -5.19957 -1.70526 -0.0322053 0.00180424 -0.00215612 -0.889186 0.457536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.19601e-06 0.00745192 3.99998 -0.00967952 0.837402 +EDGE_SE3:QUAT 193 194 4.19562 0.397859 -0.0154944 0.0022612 -0.00629826 0.0967061 0.99529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 3.81665e-05 -0.0522963 3.99983 -0.00255832 3.96328 +EDGE_SE3:QUAT 130 193 1.55749 -5.54033 0.0114403 -0.00939694 -0.0177612 -0.782371 0.622489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00059 -0.00304505 -0.0865102 4.00322 0.0162392 1.55253 +EDGE_SE3:QUAT 131 193 -2.76905 -5.4161 -0.00476839 -0.00911612 -0.0183021 -0.791406 0.610949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -0.00295619 -0.0838208 4.00333 0.0133168 1.49546 +EDGE_SE3:QUAT 194 195 4.15508 0.0599781 0.00177923 -0.000781437 0.00283416 0.0289635 0.999576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -3.30685e-06 0.0229169 3.99997 0.000332924 3.99678 +EDGE_SE3:QUAT 195 196 4.36403 -0.0595557 -0.0174667 -0.00222802 0.00582122 0.00277333 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 -4.97513e-05 0.0466486 3.99986 6.29261e-05 4.00051 +EDGE_SE3:QUAT 196 197 4.0481 -0.0977207 -0.00835172 -0.00123576 -0.00350886 -0.000991188 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 1.70662e-05 -0.0280867 3.99995 1.35583e-05 4.00019 +EDGE_SE3:QUAT 197 198 4.03713 -0.0905558 -0.0132898 0.00226823 0.0025379 -0.00143146 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.28649e-05 0.0203424 3.99997 -1.42182e-05 4.0001 +EDGE_SE3:QUAT 198 199 4.18876 -0.0973607 -0.012133 -5.6181e-05 0.000671145 -0.00114507 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.6317e-07 0.00536838 4 -3.07405e-06 4 +EDGE_SE3:QUAT 199 200 4.19759 -0.0967435 0.00568512 0.00155339 0.00366361 -0.000895504 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 2.24967e-05 0.0293268 3.99995 -1.26346e-05 4.00021 +EDGE_SE3:QUAT 200 201 4.127 -0.0966863 0.0110947 -0.000872427 -0.000701438 0.000152535 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.4487e-06 -0.00560991 4 -4.38114e-07 4.00001 +EDGE_SE3:QUAT 201 202 4.33903 -0.0944284 0.000140122 -0.00136411 0.000869403 0.000273574 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.74297e-06 0.0069597 4 9.27436e-07 4.00001 +EDGE_SE3:QUAT 202 203 4.1194 -0.0907502 0.00824404 0.00045978 -0.000381598 0.000554925 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.00802e-07 -0.00305584 4 -8.46557e-07 4 +EDGE_SE3:QUAT 203 204 4.1697 -0.0899949 -0.00844887 -0.000430278 -0.000916295 0.000475235 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.58593e-06 -0.00732792 4 -1.74973e-06 4.00001 +EDGE_SE3:QUAT 204 205 4.06137 -0.0900182 0.00104215 0.000992106 0.0040768 0.00135513 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 1.67117e-05 0.0326001 3.99993 2.24842e-05 4.00026 +EDGE_SE3:QUAT 205 206 4.38591 -0.0734211 0.0191372 -0.00034633 0.00435061 0.00500709 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -3.75631e-06 0.0348267 3.99992 8.70664e-05 4.0002 +EDGE_SE3:QUAT 206 207 4.08437 -0.0808373 0.05016 -0.000558307 -0.00231895 0.00280556 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 5.53358e-06 -0.018533 3.99998 -2.60622e-05 4.00005 +EDGE_SE3:QUAT 207 208 4.13213 -0.13214 0.0238691 -0.00138088 0.00507829 -0.0209246 0.999767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -4.0487e-05 0.0402564 3.9999 -0.000420828 3.99865 +EDGE_SE3:QUAT 208 209 4.11526 -0.311704 -0.0484792 -0.00410357 0.0278704 -0.0832378 0.996131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01168 -0.00193818 0.217109 3.99721 -0.00909201 3.98403 +EDGE_SE3:QUAT 209 210 4.20537 -0.890233 0.00951372 -0.00259366 -0.00367704 -0.21961 0.975577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -4.56128e-05 -0.0339315 3.99993 0.00389458 3.80737 +EDGE_SE3:QUAT 210 211 4.22688 -1.17933 -0.0187902 -0.00122678 0.00633831 -0.271584 0.962393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -0.000222152 0.0414027 3.99995 -0.00517646 3.70539 +EDGE_SE3:QUAT 211 212 3.96744 -1.13524 -0.0323171 0.00486438 0.0146641 -0.268349 0.963198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00349 -0.00119167 0.11988 3.99937 -0.0161994 3.71554 +EDGE_SE3:QUAT 212 213 4.16987 -1.21805 -0.012966 -0.00323583 0.00346628 -0.273229 0.961937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.80806e-05 0.0146017 4 -0.00136413 3.70143 +EDGE_SE3:QUAT 213 214 3.93035 -0.998799 -0.0119481 0.00424903 0.00153491 -0.222665 0.974885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.00942e-05 0.0223558 3.99996 -0.00287404 3.8018 +EDGE_SE3:QUAT 214 215 3.93052 -0.705903 0.00721255 0.0050293 0.0121514 -0.142146 0.989758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00254 -0.000291841 0.102802 3.99937 -0.00743144 3.92182 +EDGE_SE3:QUAT 215 216 4.31236 -0.393316 -0.00748174 -7.09237e-05 0.000656433 -0.0534375 0.998571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.25366e-07 0.0051836 4 -0.000137895 3.98858 +EDGE_SE3:QUAT 216 217 4.02563 -0.104227 -0.0194147 -0.00276417 -0.00166692 -0.00479425 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.83976e-05 -0.0134939 3.99999 3.22864e-05 3.99995 +EDGE_SE3:QUAT 217 218 4.23316 -0.0782967 0.010909 -0.00279981 0.00476142 -0.000491998 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -5.35771e-05 0.0380774 3.99991 -1.08904e-05 4.00036 +EDGE_SE3:QUAT 218 219 4.3733 -0.0853112 0.0401275 -0.00132211 -0.00524061 0.000965667 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 2.8348e-05 -0.0419134 3.99989 -2.11116e-05 4.00044 +EDGE_SE3:QUAT 219 220 4.22994 -0.0837729 0.0362453 0.00249943 -0.00451942 0.00256963 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -4.40602e-05 -0.0362343 3.99992 -4.53678e-05 4.0003 +EDGE_SE3:QUAT 220 221 4.16028 -0.0863503 0.00381854 0.00483246 -0.00166387 0.00298391 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -3.25166e-05 -0.0134835 3.99999 -1.98755e-05 4.00001 +EDGE_SE3:QUAT 221 222 4.11444 -0.0844345 -0.00734863 0.00245069 0.00528447 0.0025563 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 5.34072e-05 0.0422039 3.99989 5.55644e-05 4.00042 +EDGE_SE3:QUAT 222 223 4.14039 -0.0786663 0.0255888 0.000217565 0.00658966 0.00117159 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 6.9589e-06 0.0527221 3.99983 3.11247e-05 4.00069 +EDGE_SE3:QUAT 223 224 4.07155 -0.0874276 0.0265775 -0.00122079 -0.00257221 -0.0023513 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.22152e-05 -0.0206124 3.99997 2.40537e-05 4.00008 +EDGE_SE3:QUAT 224 225 4.07253 -0.102399 0.00524038 -0.00219621 -0.000279781 -0.00466922 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.62833e-06 -0.00236121 4 5.60372e-06 3.99991 +EDGE_SE3:QUAT 225 226 4.52457 -0.144345 -0.0195322 -0.000933527 0.00247237 -0.0135759 0.999904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -1.11021e-05 0.0196218 3.99998 -0.000132979 3.99936 +EDGE_SE3:QUAT 226 227 4.20732 -0.17166 0.0303706 -0.000270481 -0.00273176 -0.0222031 0.99975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -1.02761e-06 -0.0219106 3.99997 0.000243418 3.99815 +EDGE_SE3:QUAT 227 228 4.08052 -0.170572 0.0434482 0.00437833 -7.93575e-07 -0.010633 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.61594e-06 0.00055226 4 -3.92583e-06 3.99955 +EDGE_SE3:QUAT 228 229 4.3685 -0.0127332 0.0408177 0.00205248 -0.00221313 0.0350381 0.999381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.48792e-05 -0.0185349 3.99998 -0.000329321 3.99518 +EDGE_SE3:QUAT 229 230 4.15953 0.238529 -0.0220369 0.00395454 0.0132206 0.110174 0.993816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00237 0.000608601 0.0987063 3.99945 0.00533003 3.95388 +EDGE_SE3:QUAT 230 231 4.11244 0.626248 0.0219442 -0.00455485 -0.007155 0.189206 0.981901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 0.000249376 -0.0441007 3.99992 -0.00375209 3.85728 +EDGE_SE3:QUAT 231 232 4.29877 0.814473 0.0153276 -0.00282949 -0.00227869 0.216777 0.976214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.10235e-05 -0.00982974 4 -0.000751895 3.81205 +EDGE_SE3:QUAT 232 233 4.14367 0.714905 0.00585043 0.000488926 -0.000931523 0.207464 0.978242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.04151e-06 -0.00815859 4 -0.000871174 3.82785 +EDGE_SE3:QUAT 233 234 4.10659 0.719909 0.00321181 -0.00177319 0.00294876 0.203298 0.979111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 2.74142e-05 0.0263504 3.99996 0.00277368 3.83485 +EDGE_SE3:QUAT 234 235 4.1089 0.685659 0.0120015 -0.000190478 -0.00268201 0.202111 0.979359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 3.30259e-05 -0.0197059 3.99998 -0.00193036 3.8367 +EDGE_SE3:QUAT 235 236 4.27298 0.750545 0.0156059 0.00505066 -0.00667016 0.206428 0.978426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00086 0.000122387 -0.0621554 3.99977 -0.00672097 3.83051 +EDGE_SE3:QUAT 236 237 3.96395 0.555532 0.00720855 -0.00241067 0.00428178 0.14959 0.988736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 3.00361e-05 0.0373765 3.99992 0.00287367 3.91084 +EDGE_SE3:QUAT 237 238 3.98269 0.234975 -0.0290734 -0.00383802 0.0060422 0.0665252 0.997759 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00059 -3.61291e-05 0.0510784 3.99983 0.00172642 3.98295 +EDGE_SE3:QUAT 238 239 4.2258 0.0152572 0.00434139 -0.00340138 -0.000548181 0.0194766 0.999804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.75368e-06 -0.00358812 4 -3.23715e-05 3.99849 +EDGE_SE3:QUAT 239 240 4.2774 -0.044143 0.0231836 0.00104516 0.000514384 0.00723825 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.13137e-06 0.00402397 4 1.44598e-05 3.99979 +EDGE_SE3:QUAT 240 241 4.30933 -0.0801388 0.0365403 0.000325931 -0.00466241 0.00275521 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -4.64438e-06 -0.0373125 3.99991 -5.12483e-05 4.00032 +EDGE_SE3:QUAT 241 242 4.26868 -0.0878417 -0.00288186 0.000105071 -0.000671101 0.00051181 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.76567e-07 -0.00536946 4 -1.373e-06 4.00001 +EDGE_SE3:QUAT 242 243 4.32503 -0.112287 -0.00581438 0.00150338 0.00268038 -0.00315136 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 1.56311e-05 0.0215 3.99997 -3.3649e-05 4.00008 +EDGE_SE3:QUAT 243 244 4.40182 -0.0984171 0.0043525 -0.00237468 0.00726807 -0.00300357 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -7.27507e-05 0.0580684 3.99979 -9.02153e-05 4.00081 +EDGE_SE3:QUAT 244 245 4.36097 -0.107451 0.031699 0.00108126 0.00189246 -0.00192272 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 8.03759e-06 0.0151647 3.99999 -1.44941e-05 4.00004 +EDGE_SE3:QUAT 245 246 4.47113 -0.0935983 0.0316191 -0.00290454 -0.00118126 -0.00177913 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.3784e-05 -0.00951201 3.99999 8.38176e-06 4.00001 +EDGE_SE3:QUAT 246 247 4.44459 -0.0993887 -0.00150455 -0.00120652 -0.00485629 -0.000685201 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 2.30645e-05 -0.0388634 3.99991 1.26358e-05 4.00038 +EDGE_SE3:QUAT 247 248 4.35376 -0.10447 0.0101408 0.000539642 -0.00552203 -0.00328692 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -1.43208e-05 -0.0441589 3.99988 7.29792e-05 4.00044 +EDGE_SE3:QUAT 248 249 4.31854 -0.122313 0.0117057 0.000335751 0.00678271 -0.004651 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 3.97991e-06 0.0542874 3.99982 -0.000125949 4.00065 +EDGE_SE3:QUAT 249 250 4.12754 -0.111985 0.0459136 0.00377778 -0.00210061 -0.00441452 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.16972e-05 -0.0166041 3.99998 3.68961e-05 3.99999 +EDGE_SE3:QUAT 250 251 4.23124 -0.113646 0.0289427 0.00547672 0.0020229 0.00431099 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 4.36911e-05 0.0158989 3.99998 3.45904e-05 3.99999 +EDGE_SE3:QUAT 251 252 4.05589 0.11573 -0.0217645 0.000558811 0.00661515 0.0784595 0.996895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 9.46467e-05 0.0519168 3.99984 0.00202488 3.97605 +EDGE_SE3:QUAT 252 253 4.28677 0.622071 0.0189523 -0.000689257 -0.00499931 0.191332 0.981512 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000112559 -0.036277 3.99994 -0.00334929 3.8539 +EDGE_SE3:QUAT 253 254 4.1257 0.716577 0.0185307 -0.000504382 0.000653841 0.212931 0.977067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.25335e-06 0.00612889 4 0.000685144 3.81865 +EDGE_SE3:QUAT 254 255 4.129 0.766213 0.0106304 -0.00304251 0.00266818 0.214663 0.97668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.13198e-05 0.0274848 3.99995 0.00317497 3.81587 +EDGE_SE3:QUAT 255 256 4.24083 0.518848 0.00107513 -0.00177176 -0.00215444 0.110386 0.993885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.1731e-05 -0.0145936 3.99999 -0.000756629 3.95131 +EDGE_SE3:QUAT 256 257 4.06645 -0.0504979 0.0110416 0.000409433 -0.00105363 0.00359008 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.6344e-06 -0.00844656 4 -1.51616e-05 3.99997 +EDGE_SE3:QUAT 257 258 4.39895 -0.139165 0.00322476 0.00012787 -0.00112122 -0.0140485 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.93557e-07 -0.0089456 4 6.27842e-05 3.99923 +EDGE_SE3:QUAT 258 259 4.41541 -0.170851 0.00035207 0.000448897 -0.000176522 -0.0178467 0.999841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.99956e-07 -0.00131539 4 1.145e-05 3.99873 +EDGE_SE3:QUAT 212 258 6.72844 2.56521 0.062129 0.00430104 0.0101798 -0.995491 0.0942066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000184387 0.0175014 4.0001 0.0366101 0.0359155 +EDGE_SE3:QUAT 213 258 0.178412 4.53709 0.108162 0.00506022 0.0137562 -0.931893 0.362437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -0.000158087 0.0290535 4.00113 0.0250732 0.525923 +EDGE_SE3:QUAT 214 258 -5.7801 3.35956 0.0683855 0.00155781 0.0101385 -0.828064 0.56054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000268349 0.0226858 4.00051 0.00768687 1.2571 +EDGE_SE3:QUAT 259 260 4.16847 -0.153224 0.0167778 -0.00116052 0.00916191 -0.0167535 0.999817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00133 -7.59556e-05 0.0730523 3.99967 -0.000614065 4.00021 +EDGE_SE3:QUAT 211 259 6.95468 -0.716696 -0.0759513 0.00795826 -0.0142604 0.980784 0.194411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99941 -0.000178577 -0.0344213 4.00131 0.0398347 0.151915 +EDGE_SE3:QUAT 212 259 2.36781 1.91028 0.0192438 0.00387161 0.00995079 -0.997014 0.0764767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000171569 0.0156591 4 0.0368704 0.0237986 +EDGE_SE3:QUAT 213 259 -3.1626 1.72061 0.0267915 0.00493357 0.0131947 -0.938283 0.345581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 -0.000100794 0.0272926 4.001 0.0256944 0.478151 +EDGE_SE3:QUAT 260 261 4.44269 -0.175287 0.0108527 0.000917515 0.000483241 -0.0120419 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.78299e-06 0.00399766 4 -2.43286e-05 3.99942 +EDGE_SE3:QUAT 211 260 3.17627 1.01792 0.0319254 -0.00111568 -0.0136723 0.977454 0.210704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000227938 0.00372415 3.99938 0.0505079 0.17826 +EDGE_SE3:QUAT 212 260 -1.77353 1.43657 -0.00298821 0.0128768 0.0117061 -0.998079 0.0594552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99921 0.000399384 0.0517991 4.00252 0.0403455 0.0152215 +EDGE_SE3:QUAT 213 260 -6.45386 -0.862265 -0.0273284 0.0129111 0.0176708 -0.943718 0.330026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99878 -0.00112889 0.064421 4.0045 0.0218251 0.437035 +EDGE_SE3:QUAT 261 262 4.4393 -0.132065 0.0200616 0.00427106 -0.00150222 -0.00150246 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -2.55254e-05 -0.0119405 3.99999 9.17992e-06 4.00003 +EDGE_SE3:QUAT 210 261 5.12479 1.79076 0.0464208 0.00132227 -0.00921996 0.8775 0.479486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 7.85842e-05 -0.0149051 4.00032 0.0135771 0.91981 +EDGE_SE3:QUAT 211 261 -0.807499 3.0042 0.0612096 -0.00117399 -0.0125079 0.974815 0.222662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000196645 0.00392541 3.99949 0.0459237 0.198875 +EDGE_SE3:QUAT 212 261 -6.196 1.07225 -0.11209 0.013357 0.0108674 -0.998718 0.047598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99919 0.000402536 0.0536181 4.0027 0.0381863 0.010148 +EDGE_SE3:QUAT 262 263 4.4607 -0.0734846 0.0199843 -0.00268736 -0.000663614 0.00461949 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.91293e-06 -0.00515972 4 -1.183e-05 3.99992 +EDGE_SE3:QUAT 210 262 2.8188 5.60226 0.116937 0.00501243 -0.00584113 0.876999 0.48043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000382643 -0.0308833 4.00063 -0.00378986 0.923548 +EDGE_SE3:QUAT 211 262 -4.75013 5.04454 0.10447 0.00103521 -0.00871597 0.974616 0.223713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000109398 -0.0052212 3.99991 0.0288196 0.200419 +EDGE_SE3:QUAT 263 264 4.31029 -0.068407 0.0158338 -0.00237266 0.00089584 0.0057518 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.64581e-06 0.00733009 4 2.11901e-05 3.99988 +EDGE_SE3:QUAT 264 265 4.26652 -0.0674887 0.013629 0.00229029 -0.00145181 0.00974871 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.31962e-05 -0.0118807 3.99999 -5.82247e-05 3.99966 +EDGE_SE3:QUAT 265 266 4.30859 -0.0622959 0.0160674 0.00202833 -0.000236925 0.0103895 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.24671e-06 -0.00214794 4 -1.1592e-05 3.99957 +EDGE_SE3:QUAT 266 267 4.122 -0.0497399 0.0206412 -0.000111976 -0.00206679 0.00715021 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.65728e-06 -0.0165237 3.99998 -5.90752e-05 3.99986 +EDGE_SE3:QUAT 267 268 4.18984 -0.0786115 0.00643439 -0.00335966 -0.00261766 -0.0030819 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 3.49466e-05 -0.0210654 3.99997 3.1969e-05 4.00007 +EDGE_SE3:QUAT 268 269 4.21899 -0.126151 -0.014043 0.00276015 0.0136588 -0.00402145 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00296 0.000133379 0.109471 3.99925 -0.000208243 4.00293 +EDGE_SE3:QUAT 269 270 4.22526 -0.110962 0.0221225 0.000970985 -0.00315645 -0.00356929 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -1.30852e-05 -0.0252104 3.99996 4.52028e-05 4.00011 +EDGE_SE3:QUAT 270 271 4.04226 -0.117136 0.0197271 0.00131181 -0.00103278 -0.00258537 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.4493e-06 -0.00822143 4 1.06436e-05 3.99999 +EDGE_SE3:QUAT 271 272 4.03281 -0.0957075 0.01666 -0.00177679 9.41615e-05 0.000837589 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.90186e-07 0.000771146 4 3.25052e-07 4 +EDGE_SE3:QUAT 272 273 4.16605 0.057578 0.015602 -0.00215183 -0.00101799 0.0567638 0.998385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.64309e-06 -0.00664195 4 -0.000174311 3.98712 +EDGE_SE3:QUAT 273 274 4.10884 0.435923 0.00519869 -0.000915244 -0.000150036 0.150013 0.988684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.70768e-07 0.000462861 4 7.69305e-05 3.90998 +EDGE_SE3:QUAT 274 275 4.04287 0.623622 0.00420923 -0.0017561 0.00152773 0.183034 0.983104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 6.12593e-07 0.015384 3.99998 0.00150619 3.86605 +EDGE_SE3:QUAT 275 276 4.16157 0.633172 0.0165798 0.00322774 -0.00807115 0.186226 0.982468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00112 0.000211312 -0.0683034 3.99974 -0.00647592 3.86245 +EDGE_SE3:QUAT 276 277 4.18736 0.593982 0.00637571 0.000351869 0.00258878 0.154733 0.987953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.59483e-05 0.0193284 3.99998 0.00145915 3.90432 +EDGE_SE3:QUAT 277 278 4.15026 0.282387 -0.0378052 -0.0045458 0.00990321 0.0692237 0.997542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00162 -1.62064e-05 0.0824501 3.99957 0.00288238 3.98253 +EDGE_SE3:QUAT 278 279 4.31014 -0.00255887 0.00732215 -0.00365509 0.0039887 0.00877236 0.999947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -5.58442e-05 0.0322919 3.99993 0.000140797 3.99995 +EDGE_SE3:QUAT 279 280 4.42286 -0.117242 0.0385452 -0.00189265 -3.2375e-05 -0.00935354 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.12459e-07 -0.000471388 4 2.53557e-06 3.99965 +EDGE_SE3:QUAT 280 281 4.31226 -0.111641 0.024222 -0.00201595 -0.00559603 -0.00476719 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 4.17002e-05 -0.0448868 3.99987 0.000105596 4.00041 +EDGE_SE3:QUAT 281 282 4.39007 -0.100036 0.0164513 0.00113869 -0.00759917 -0.00168847 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 -3.69619e-05 -0.0607821 3.99977 5.29166e-05 4.00091 +EDGE_SE3:QUAT 282 283 4.34955 -0.10984 -0.0177821 0.00479085 0.00181965 -0.00146085 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.50217e-05 0.0146408 3.99999 -1.03306e-05 4.00005 +EDGE_SE3:QUAT 283 284 4.2103 -0.0862729 0.0131985 -0.000810226 0.00585234 -0.00150491 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 -2.02046e-05 0.0468095 3.99986 -3.58968e-05 4.00054 +EDGE_SE3:QUAT 284 285 4.26653 -0.102662 0.0359425 0.00177251 0.00609376 -0.00159022 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 4.1848e-05 0.0487898 3.99985 -3.72355e-05 4.00058 +EDGE_SE3:QUAT 285 286 4.24608 -0.115177 0.0174515 0.00111197 -0.00194404 -0.000953673 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -8.72422e-06 -0.0155397 3.99998 7.5089e-06 4.00006 +EDGE_SE3:QUAT 286 287 4.29112 -0.0982089 -0.0137219 -0.00145725 -0.00101643 -0.00547595 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.87924e-06 -0.00822681 4 2.25753e-05 3.9999 +EDGE_SE3:QUAT 287 288 4.50549 -0.134176 0.00247378 -0.00320651 0.00345986 -0.0102534 0.999936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -4.64102e-05 0.0272807 3.99995 -0.000140096 3.99977 +EDGE_SE3:QUAT 288 289 4.33179 -0.141371 0.0476963 0.00142828 -0.00194401 -0.00890171 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.17549e-05 -0.0153978 3.99999 6.84347e-05 3.99974 +EDGE_SE3:QUAT 289 290 4.13129 -0.109624 0.0486305 0.00277061 -0.00428021 0.000116679 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -4.74024e-05 -0.0342473 3.99993 -7.79932e-07 4.00029 +EDGE_SE3:QUAT 290 291 3.99762 -0.00740395 0.0221822 0.00335774 -0.000909898 0.0379923 0.999272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.45905e-05 -0.00879269 3.99999 -0.000176532 3.99425 +EDGE_SE3:QUAT 291 292 4.33808 0.258448 -0.0440778 0.00111712 0.00997279 0.0951373 0.995414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00149 0.000260743 0.0774587 3.99965 0.0036534 3.96529 +EDGE_SE3:QUAT 292 293 4.33752 0.445128 0.0163056 -0.00191476 -0.00109188 0.138151 0.990409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.96626e-06 -0.00535219 4 -0.000290817 3.92366 +EDGE_SE3:QUAT 293 294 4.03666 0.546552 0.0358369 0.0012551 -0.00284687 0.168157 0.985755 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 2.11651e-05 -0.0243015 3.99997 -0.00208645 3.88704 +EDGE_SE3:QUAT 294 295 4.22441 0.618329 -0.000279242 -0.00110672 -0.0008316 0.181688 0.983355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.11652e-06 -0.00396626 4 -0.000277071 3.86796 +EDGE_SE3:QUAT 295 296 4.25593 0.544496 -0.0171181 0.00334492 0.00316691 0.17116 0.985232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.87742e-05 0.0174939 3.99999 0.00126933 3.88289 +EDGE_SE3:QUAT 296 297 4.0578 0.760748 0.00452309 -0.00123828 0.000859092 0.237565 0.971371 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.58524e-07 0.0096965 3.99999 0.00126727 3.77428 +EDGE_SE3:QUAT 297 298 4.07231 0.93296 -0.00268404 -0.00383971 0.00207627 0.259589 0.965709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 2.18081e-06 0.0263842 3.99995 0.00386386 3.73063 +EDGE_SE3:QUAT 298 299 3.93533 0.861204 0.0218846 -0.000757118 -0.00510579 0.228276 0.973583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000131842 -0.0356958 3.99995 -0.00387059 3.79188 +EDGE_SE3:QUAT 299 300 4.15187 0.454861 0.0115351 -0.000985426 0.00177603 0.108976 0.994042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.5829e-06 0.0152346 3.99999 0.000848816 3.95255 +EDGE_SE3:QUAT 300 301 4.06957 0.0254715 -0.0489628 -0.00458567 0.00997434 0.0129916 0.999855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00154 -0.000153875 0.0805156 3.99959 0.000513959 4.00094 +EDGE_SE3:QUAT 301 302 4.44318 -0.166942 -0.00433245 0.000143766 -0.000618959 -0.0162264 0.999868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.00889e-07 -0.00492174 4 3.98515e-05 3.99895 +EDGE_SE3:QUAT 302 303 4.07864 -0.143372 0.0177442 -0.000554099 -0.0032436 -0.015489 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 3.29109e-06 -0.0260434 3.99996 0.000201816 3.99921 +EDGE_SE3:QUAT 303 304 4.21227 -0.157456 0.0380709 0.00274319 -0.00370084 -0.0131704 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -4.40384e-05 -0.0291665 3.99995 0.000192007 3.99952 +EDGE_SE3:QUAT 304 305 4.20162 -0.113497 -0.00573539 -0.000861618 -0.00215189 -0.00302058 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 7.09807e-06 -0.0172464 3.99998 2.59679e-05 4.00004 +EDGE_SE3:QUAT 305 306 4.30341 -0.107617 -0.0181289 0.00347345 0.00387105 -0.000924421 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 5.35498e-05 0.031008 3.99994 -1.30886e-05 4.00024 +EDGE_SE3:QUAT 306 307 4.30366 -0.0900398 0.0200236 -0.00146559 0.0119341 -0.00060884 0.999928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00227 -7.21729e-05 0.0955091 3.99943 -3.41294e-05 4.00228 +EDGE_SE3:QUAT 307 308 4.32755 -0.0859062 0.0431492 -0.00334746 0.000667906 -0.00033679 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -8.9164e-06 0.00532964 4 -9.32422e-07 4.00001 +EDGE_SE3:QUAT 308 309 4.32343 -0.0825974 0.0247667 -0.00164498 -0.00468691 7.00531e-05 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 3.08842e-05 -0.0374966 3.99991 -2.18095e-06 4.00035 +EDGE_SE3:QUAT 309 310 4.45053 -0.0924299 -0.00536124 -0.0010033 -0.00124154 -0.000289439 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.97425e-06 -0.00993584 3.99999 1.40096e-06 4.00002 +EDGE_SE3:QUAT 310 311 4.2233 -0.0887951 0.0249885 0.00102577 -0.00104698 -0.00095061 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.31284e-06 -0.00836411 4 4.00062e-06 4.00001 +EDGE_SE3:QUAT 311 312 4.19078 -0.0823109 0.0455635 0.000761806 0.00124788 -0.000767554 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.77748e-06 0.00999006 3.99999 -3.80641e-06 4.00002 +EDGE_SE3:QUAT 312 313 4.13227 -0.0993609 0.0452191 0.00154741 -0.00642996 -0.00244091 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -4.21938e-05 -0.0514011 3.99984 6.42748e-05 4.00064 +EDGE_SE3:QUAT 313 314 4.07236 -0.128788 0.0114808 -3.99201e-05 -0.00334925 -0.0184785 0.999824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -4.43973e-06 -0.0267902 3.99996 0.000247525 3.99881 +EDGE_SE3:QUAT 314 315 4.20467 -0.348621 -0.0367882 -0.00585057 0.0198364 -0.0892895 0.995791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00553 -0.00121631 0.150733 3.99868 -0.00668518 3.97378 +EDGE_SE3:QUAT 315 316 4.14301 -0.648188 0.011781 0.00147695 0.00270694 -0.157284 0.987549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.4153e-05 0.0235993 3.99997 -0.00190736 3.90119 +EDGE_SE3:QUAT 316 317 4.01678 -0.757194 0.0199003 0.00407191 -0.00399094 -0.175071 0.984539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -7.72422e-05 -0.0220908 3.99998 0.00164152 3.87752 +EDGE_SE3:QUAT 270 316 2.46821 6.65451 -4.85305e-05 0.00154709 0.0100041 -0.865464 0.500868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000141978 0.0180976 4.00043 0.0126136 1.0037 +EDGE_SE3:QUAT 271 316 -1.59731 6.75708 -0.0336223 -7.94941e-05 0.00925941 -0.864062 0.5033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 1.99672e-06 0.00902922 4.00017 0.0160298 1.01341 +EDGE_SE3:QUAT 317 318 3.89131 -0.821981 -0.000883396 0.000124018 0.00727257 -0.213847 0.97684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 -0.000247949 0.0545527 3.99986 -0.00570016 3.81782 +EDGE_SE3:QUAT 269 317 4.06327 3.43319 0.0111082 0.00177556 0.00437259 -0.940902 0.338647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.34312e-05 0.00957366 4.00012 0.00842395 0.458778 +EDGE_SE3:QUAT 270 317 -0.197752 3.5365 -0.0145667 -0.00171011 0.00445562 -0.939738 0.341861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.79896e-05 -0.00650662 3.99992 0.016964 0.46757 +EDGE_SE3:QUAT 271 317 -4.22886 3.63142 -0.036601 -0.00306151 0.00381059 -0.938927 0.344081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.01776e-05 -0.0129793 3.99994 0.0183522 0.473704 +EDGE_SE3:QUAT 318 319 4.04481 -1.1561 -0.0385926 0.00183712 0.00858109 -0.272689 0.962062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -0.000419193 0.0668658 3.99982 -0.00902577 3.70368 +EDGE_SE3:QUAT 268 318 4.74758 1.46828 -0.0240185 -0.00557237 0.0114899 -0.992074 0.125004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.00016073 -0.0226303 3.99964 0.0496593 0.0632585 +EDGE_SE3:QUAT 269 318 0.531743 1.58654 -0.00189785 0.00786703 0.00709101 -0.991549 0.129298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 2.65585e-05 0.0323682 4.0011 0.0191909 0.0672338 +EDGE_SE3:QUAT 270 318 -3.69705 1.68491 -0.0023834 0.00447784 0.00621339 -0.991141 0.13259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 5.65497e-05 0.0184931 4.00034 0.0191043 0.0705014 +EDGE_SE3:QUAT 319 320 4.08136 -1.13209 -0.029277 -0.00104865 0.00466334 -0.259228 0.965804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.000117306 0.0304954 3.99997 -0.00364244 3.73143 +EDGE_SE3:QUAT 267 319 4.73534 1.48648 0.0096533 -0.00341769 -0.00541167 0.988161 0.153286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.57998e-05 0.0139888 3.99995 0.0244785 0.0941895 +EDGE_SE3:QUAT 268 319 0.551973 1.57707 0.010979 -0.000360248 -0.00835178 0.988537 0.150747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.73899e-05 0.00125989 3.99975 0.031948 0.0911601 +EDGE_SE3:QUAT 269 319 -3.67098 1.68167 -0.0944835 -0.0144061 -0.00791254 0.989105 0.146289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.000938277 0.0592617 4.00213 0.0465104 0.0870437 +EDGE_SE3:QUAT 320 321 4.01332 -0.957788 -0.00441717 -0.00127809 -0.00153434 -0.213289 0.976987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -6.43737e-06 -0.0146189 3.99999 0.00164434 3.81809 +EDGE_SE3:QUAT 266 320 5.2755 3.78125 0.00612908 -0.00892366 -0.00682027 0.917363 0.397894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000224896 0.0396859 3.9999 0.0410126 0.634173 +EDGE_SE3:QUAT 267 320 1.19119 3.81436 -0.0211797 -0.00689108 -0.00609515 0.914438 0.404622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 9.16224e-05 0.0302334 3.99986 0.0336489 0.655443 +EDGE_SE3:QUAT 268 320 -3.02214 3.88686 0.0169258 -0.00342891 -0.00808006 0.915748 0.401657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00011577 0.012424 3.99974 0.0292871 0.645616 +EDGE_SE3:QUAT 321 322 3.92935 -0.674141 0.00248737 0.00178421 -0.00582751 -0.131377 0.991314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -0.000130949 -0.0426415 3.9999 0.00271489 3.93141 +EDGE_SE3:QUAT 267 321 -0.792472 7.39652 -0.0381247 -0.00443527 -0.00923921 0.807218 0.590164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -0.000182981 0.00910346 3.99984 0.0226971 1.39347 +EDGE_SE3:QUAT 322 323 4.21637 -0.407665 0.0198309 0.00505245 -0.0143583 -0.0600984 0.998076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00296 -0.000557777 -0.110677 3.99927 0.00331351 3.98861 +EDGE_SE3:QUAT 323 324 3.99592 -0.10265 -0.0317575 0.000600296 0.00336027 0.00289738 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 8.84566e-06 0.026862 3.99995 3.90715e-05 4.00015 +EDGE_SE3:QUAT 324 325 4.16091 -0.0684943 0.014141 -0.00010583 0.00615356 0.00723728 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 3.97298e-06 0.0492403 3.99985 0.000178164 4.0004 +EDGE_SE3:QUAT 325 326 4.38979 -0.0520165 0.036154 -0.00150091 -0.00209506 0.00834286 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.32931e-05 -0.0166086 3.99998 -6.92294e-05 3.99979 +EDGE_SE3:QUAT 326 327 4.36148 -0.0513018 -0.000746205 -0.000400753 -0.00492573 0.00862346 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 1.28996e-05 -0.0393633 3.9999 -0.000169934 4.00009 +EDGE_SE3:QUAT 327 328 4.42586 -0.0671727 -0.0487709 0.00234328 -0.00260228 0.00566928 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -2.37087e-05 -0.020977 3.99997 -5.92305e-05 3.99998 +EDGE_SE3:QUAT 328 329 4.46544 -0.0839445 -0.0326148 -0.00103887 0.00673728 0.000122418 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -2.7882e-05 0.0539082 3.99982 2.16925e-06 4.00073 +EDGE_SE3:QUAT 329 330 4.01157 -0.0872898 0.0182026 -0.000912043 0.00614054 0.0013489 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 -2.1201e-05 0.0491454 3.99985 3.23366e-05 4.0006 +EDGE_SE3:QUAT 330 331 4.46181 -0.0862588 0.0406272 -1.54029e-05 -0.0023111 0.00264834 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 4.8187e-07 -0.0184884 3.99998 -2.44849e-05 4.00006 +EDGE_SE3:QUAT 331 332 4.42343 -0.0813695 0.00224713 -0.000586069 -0.0047214 0.00498752 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 1.3722e-05 -0.0377376 3.99991 -9.44133e-05 4.00026 +EDGE_SE3:QUAT 332 333 4.46335 -0.0451506 -0.0398647 0.00130195 -0.00357379 0.00888352 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -1.5989e-05 -0.0287269 3.99995 -0.000127414 3.99989 +EDGE_SE3:QUAT 333 334 4.18533 -0.0567575 -0.0139263 0.00105125 0.00983836 0.00847153 0.999915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00154 6.09898e-05 0.0786179 3.99961 0.00033562 4.00126 +EDGE_SE3:QUAT 334 335 4.26514 -0.0784418 0.0404805 -0.00305899 -0.00114615 -0.00411662 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.41989e-05 -0.00932001 3.99999 1.91882e-05 3.99995 +EDGE_SE3:QUAT 335 336 4.18669 -0.181956 0.0496422 -0.000210309 0.0194928 -0.03786 0.999093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00605 -0.000361073 0.155717 3.9985 -0.00295867 4.00032 +EDGE_SE3:QUAT 336 337 4.17102 -0.446759 -0.0405121 -0.00592988 0.0125758 -0.116625 0.993079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0019 -0.000635801 0.0903682 3.99956 -0.0050949 3.94763 +EDGE_SE3:QUAT 337 338 4.09109 -0.790476 -0.00122477 -0.00106666 0.00386363 -0.192956 0.981199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -7.00313e-05 0.0267913 3.99997 -0.00244899 3.85125 +EDGE_SE3:QUAT 338 339 3.94397 -0.844677 0.013613 0.00342786 0.000851862 -0.204508 0.978859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.65692e-05 0.0145696 3.99998 -0.00176106 3.83276 +EDGE_SE3:QUAT 339 340 4.09373 -1.07264 -0.00026232 0.00606683 0.0176155 -0.25021 0.968012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00514 -0.00157523 0.145526 3.999 -0.0184033 3.75486 +EDGE_SE3:QUAT 340 341 4.10712 -1.20608 0.00532001 0.000510572 0.00217047 -0.275095 0.961414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -2.70297e-05 0.0170311 3.99999 -0.00232414 3.69736 +EDGE_SE3:QUAT 341 342 3.86827 -1.03456 -0.00227357 -0.00130171 -0.00169972 -0.247399 0.968911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.20966e-05 -0.0160757 3.99999 0.00209369 3.75524 +EDGE_SE3:QUAT 342 343 3.88042 -0.867111 -0.0113745 0.00352553 -0.00215164 -0.18157 0.983369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.84182e-05 -0.00885595 4 0.000545419 3.86815 +EDGE_SE3:QUAT 343 344 4.29446 -0.529104 -0.0411828 0.00299223 0.0219176 -0.0835703 0.996256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00776 -0.000712667 0.176796 3.9981 -0.00740632 3.97986 +EDGE_SE3:QUAT 344 345 4.07379 -0.202338 0.022851 -0.00223154 0.00190134 -0.0215714 0.999763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.78585e-05 0.0146227 3.99999 -0.000155789 3.99819 +EDGE_SE3:QUAT 345 346 4.37846 -0.0958049 0.0220177 -0.000497387 -0.00896099 0.00120768 0.999959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00128 2.01738e-05 -0.0717007 3.99968 -4.42894e-05 4.00128 +EDGE_SE3:QUAT 346 347 4.23828 -0.0630989 0.0233306 0.000835408 -0.00857393 0.0089965 0.999922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 -1.28178e-05 -0.0686909 3.99971 -0.000307873 4.00086 +EDGE_SE3:QUAT 347 348 4.40398 -0.056995 -0.0167797 0.00217226 0.00135525 0.00792047 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.18143e-05 0.0106345 3.99999 4.19348e-05 3.99978 +EDGE_SE3:QUAT 348 349 4.30225 -0.0781711 0.00342708 -0.00131644 0.00820772 0.00263513 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00107 -3.90304e-05 0.0657181 3.99973 8.4536e-05 4.00105 +EDGE_SE3:QUAT 349 350 4.37532 -0.0898926 0.0345255 0.0019886 0.00580594 0.00295904 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 4.84982e-05 0.0463815 3.99987 7.02165e-05 4.0005 +EDGE_SE3:QUAT 350 351 4.25914 -0.0778803 0.0284136 0.000561547 -0.00368704 0.00217428 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -7.57878e-06 -0.0295122 3.99995 -3.19104e-05 4.0002 +EDGE_SE3:QUAT 351 352 4.22069 -0.0522786 -0.00855609 -0.00421066 -0.000313052 0.00324928 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.81835e-06 -0.00234013 4 -3.72183e-06 3.99996 +EDGE_SE3:QUAT 352 353 4.33578 -0.0577853 0.0124599 -0.0038391 0.0031381 0.00521823 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -4.75562e-05 0.0253445 3.99996 6.54205e-05 4.00005 +EDGE_SE3:QUAT 353 354 4.51006 -0.0655085 0.0365978 0.000575981 -0.00561749 0.00549855 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -8.79161e-06 -0.0449808 3.99987 -0.000123302 4.00038 +EDGE_SE3:QUAT 354 355 4.31791 -0.0771157 0.0424788 0.00399864 0.00392776 0.00569098 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 6.41807e-05 0.0311484 3.99994 8.9846e-05 4.00011 +EDGE_SE3:QUAT 355 356 4.15615 -0.0758104 0.0357909 0.000860032 -0.00778009 0.000738925 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00097 -2.57175e-05 -0.0622614 3.99976 -2.17688e-05 4.00097 +EDGE_SE3:QUAT 356 357 4.15086 -0.110542 0.0108242 0.0012301 -0.00423714 -0.000372945 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -2.10098e-05 -0.0338937 3.99993 6.85102e-06 4.00029 +EDGE_SE3:QUAT 357 358 4.12678 0.0050621 -0.0166868 0.00474036 0.0228158 0.0408784 0.998892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.008 0.000927144 0.180054 3.99802 0.00373897 4.0014 +EDGE_SE3:QUAT 358 359 4.36468 0.414078 0.0370255 -0.00194962 -0.00414064 0.146661 0.989176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 7.53759e-05 -0.0286811 3.99996 -0.00199377 3.91417 +EDGE_SE3:QUAT 359 360 4.37904 0.744576 0.0345528 -0.00133011 -0.00582341 0.199217 0.979937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 0.000160275 -0.0407491 3.99993 -0.0038608 3.84166 +EDGE_SE3:QUAT 360 361 4.21575 0.702862 0.00072903 0.000509646 -0.00245217 0.207275 0.97828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.55282e-05 -0.0195986 3.99998 -0.00202986 3.82824 +EDGE_SE3:QUAT 361 362 4.09728 0.741916 -0.00310148 0.000136015 0.00480921 0.218038 0.975928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000111337 0.0354207 3.99994 0.00374629 3.81015 +EDGE_SE3:QUAT 362 363 4.13355 0.769715 0.00358245 -0.00355135 0.000166981 0.216454 0.976286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.78705e-05 0.0101794 3.99999 0.00143049 3.81261 +EDGE_SE3:QUAT 363 364 4.26442 0.775544 0.00387953 0.00039844 -0.00645878 0.21178 0.977296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 0.000191408 -0.0492221 3.99988 -0.00512287 3.8212 +EDGE_SE3:QUAT 364 365 4.28029 0.700251 -0.00656348 -8.59463e-05 -0.00160925 0.176857 0.984235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.06438e-05 -0.0120962 3.99999 -0.00104609 3.87492 +EDGE_SE3:QUAT 365 366 4.35984 0.33602 0.0118924 0.000736237 0.0165452 0.0900793 0.995797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00422 0.000626019 0.130081 3.99899 0.00584389 3.97177 +EDGE_SE3:QUAT 366 367 4.12048 0.132493 0.018143 -0.00679433 -0.00473453 0.0418753 0.999089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 0.000132201 -0.0343659 3.99993 -0.000698299 3.99328 +EDGE_SE3:QUAT 367 368 4.26712 -0.0089696 -0.0125015 -0.00151937 -0.00607757 0.0121127 0.999907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 4.73813e-05 -0.048395 3.99985 -0.000294079 4 +EDGE_SE3:QUAT 368 369 4.38049 -0.0390591 -0.0175017 -0.000905399 0.00557864 0.00634941 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -1.54982e-05 0.0447002 3.99988 0.000141349 4.00034 +EDGE_SE3:QUAT 369 370 4.01539 -0.0911238 0.0145181 -0.000408693 -0.0036107 -0.00527775 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 4.25678e-06 -0.0289116 3.99995 7.61981e-05 4.0001 +EDGE_SE3:QUAT 370 371 4.39371 -0.160677 0.0423008 0.00402479 0.000684899 -0.0138897 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.26341e-05 0.00614823 4 -4.41933e-05 3.99924 +EDGE_SE3:QUAT 371 372 4.26307 -0.150118 0.0215734 -0.000852889 -0.00154438 -0.0127321 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.60067e-06 -0.0124824 3.99999 7.96863e-05 3.99939 +EDGE_SE3:QUAT 372 373 4.36806 -0.146309 -0.00774928 0.00265773 -0.000348716 -0.0084105 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.25236e-06 -0.00252118 4 1.02324e-05 3.99972 +EDGE_SE3:QUAT 373 374 4.25076 -0.0835171 -0.00413294 -0.00154767 0.00637837 -0.000162594 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 -3.96644e-05 0.051031 3.99984 -5.66165e-06 4.00065 +EDGE_SE3:QUAT 374 375 4.24565 -0.106624 0.0261299 0.000667652 0.00617351 -0.0001579 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 1.63519e-05 0.0493959 3.99985 -3.29056e-06 4.00061 +EDGE_SE3:QUAT 375 376 4.28375 -0.0965944 0.0464592 -0.00161284 -0.00311733 -0.00059639 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.99868e-05 -0.0249509 3.99996 7.06569e-06 4.00015 +EDGE_SE3:QUAT 376 377 4.12781 -0.0788323 0.0189083 -0.00301763 -0.0021006 -0.000256777 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.5348e-05 -0.0168142 3.99998 1.83938e-06 4.00007 +EDGE_SE3:QUAT 377 378 4.0124 -0.0914897 0.0199525 0.00174981 -0.00351274 0.000231319 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -2.45277e-05 -0.0281078 3.99995 -2.73318e-06 4.0002 +EDGE_SE3:QUAT 378 379 4.20297 -0.0950665 0.0237341 0.00372459 -6.01737e-05 0.00453335 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.39884e-06 -0.000683978 4 -1.70286e-06 3.99992 +EDGE_SE3:QUAT 379 380 4.09586 0.0197491 0.0329883 0.00162667 0.00845381 0.0416004 0.999097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 0.000123815 0.0666596 3.99973 0.00138344 3.99419 +EDGE_SE3:QUAT 380 381 4.12653 0.259535 0.0122818 0.00283619 0.000907163 0.109325 0.994002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.8002e-06 0.00343636 4 0.000117675 3.95219 +EDGE_SE3:QUAT 381 382 4.37701 0.680543 0.0108775 -0.00423983 -0.00524463 0.192667 0.981241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 0.000133569 -0.0300825 3.99997 -0.00250856 3.85174 +EDGE_SE3:QUAT 382 383 3.98817 0.628908 0.008313 0.000661471 -0.00170311 0.186794 0.982397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 9.54928e-06 -0.0143664 3.99999 -0.00136512 3.86048 +EDGE_SE3:QUAT 383 384 4.26137 0.606004 -0.00391021 -0.000291874 0.00120614 0.157446 0.987527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.29023e-06 0.00983494 3.99999 0.000779114 3.90087 +EDGE_SE3:QUAT 384 385 4.14869 0.293343 -0.0198179 0.00193194 -0.00052869 0.0884011 0.996083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.54125e-06 -0.00621877 4 -0.000304309 3.96875 +EDGE_SE3:QUAT 385 386 4.15384 0.0724005 0.00103878 -0.000461814 -0.000265464 0.0284089 0.999596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.83735e-07 -0.00196379 4 -2.71376e-05 3.99677 +EDGE_SE3:QUAT 386 387 4.25353 -0.0988744 0.0159082 -0.00040788 -0.000912524 -0.00771914 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.34342e-06 -0.00733734 4 2.83587e-05 3.99978 +EDGE_SE3:QUAT 342 386 -2.15714 6.94522 0.172843 0.00576993 0.0124822 -0.859465 0.511009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.000854398 0.0435191 4.00152 0.00306514 1.04519 +EDGE_SE3:QUAT 387 388 4.13615 -0.116907 0.00996361 -0.0010603 -0.00516332 -0.00838944 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 1.65897e-05 -0.0414127 3.99989 0.000173226 4.00015 +EDGE_SE3:QUAT 341 387 1.69362 3.9021 0.0652967 0.00841429 0.00866563 -0.961421 0.274816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99958 -0.000326972 0.0386832 4.00159 0.0111944 0.302545 +EDGE_SE3:QUAT 342 387 -4.2938 3.27686 0.0951386 0.00458863 0.0123427 -0.863391 0.504364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000615625 0.0365752 4.00122 0.00713204 1.01806 +EDGE_SE3:QUAT 388 389 4.1761 -0.0877881 0.00590456 -0.00088067 0.0173485 -0.00205478 0.999847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00482 -7.62179e-05 0.138912 3.9988 -0.000149529 4.0048 +EDGE_SE3:QUAT 340 388 3.42761 1.33767 0.0234917 -0.00349025 -0.00907978 0.999915 0.00870473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000123413 0.0139642 3.99985 0.0365561 0.000685959 +EDGE_SE3:QUAT 341 388 -1.90357 1.81044 -0.00619571 0.0032429 0.00878117 -0.963743 0.26667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 4.83048e-05 0.0156115 4.00031 0.0226146 0.284664 +EDGE_SE3:QUAT 342 388 -6.42457 -0.244877 0.0291347 -0.000415497 0.0112868 -0.867421 0.497446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 4.04647e-05 0.00895847 4.00019 0.0210271 0.990067 +EDGE_SE3:QUAT 389 390 4.21929 -0.109811 0.0119327 0.00251123 -0.00348813 -0.000488697 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -3.51615e-05 -0.0278912 3.99995 7.54757e-06 4.00019 +EDGE_SE3:QUAT 339 389 4.19343 0.600705 0.0342736 -0.00475711 -0.00990597 0.965319 0.260841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.23033e-05 0.0194639 3.99958 0.0422955 0.272727 +EDGE_SE3:QUAT 340 389 -0.727287 1.51211 -0.000660236 -0.0208719 -0.00954503 0.999679 0.0107502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99829 0.000904799 0.0834981 4.00651 0.0400579 0.00260637 +EDGE_SE3:QUAT 341 389 -5.50754 -0.230416 -0.0335071 0.0197982 0.0143636 -0.963975 0.264867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99821 -0.00192324 0.0891774 4.00779 0.00860439 0.282794 +EDGE_SE3:QUAT 390 391 4.2718 -0.0972414 0.0227513 0.00100328 -0.0014188 -0.00065535 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.72033e-06 -0.0113426 3.99999 3.76431e-06 4.00003 +EDGE_SE3:QUAT 338 390 5.61776 1.48666 0.0693824 -0.00086778 -0.0110287 0.891204 0.453469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.000126292 -0.00386144 4.00002 0.0256493 0.822805 +EDGE_SE3:QUAT 339 390 0.594108 2.80819 0.0309041 -0.000824987 -0.00838603 0.96522 0.261304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -9.98973e-05 0.00242263 3.99979 0.0295632 0.273359 +EDGE_SE3:QUAT 340 390 -4.93838 1.7061 -0.161919 -0.0175719 -0.00707483 0.999761 0.010887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99879 0.000574808 0.070296 4.00468 0.0298712 0.00193269 +EDGE_SE3:QUAT 391 392 4.22275 -0.0864155 0.0171784 -0.00130839 -0.00140762 0.00100423 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 7.40094e-06 -0.0112452 3.99999 -5.70593e-06 4.00003 +EDGE_SE3:QUAT 338 391 3.18589 4.99407 0.131064 0.000999198 -0.0105109 0.89108 0.453723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 1.17596e-05 -0.0128808 4.00029 0.0191618 0.823682 +EDGE_SE3:QUAT 339 391 -3.03007 5.0548 0.0703007 0.000694983 -0.00782275 0.965096 0.261777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -8.66654e-05 -0.00417375 3.99995 0.0247055 0.274283 +EDGE_SE3:QUAT 392 393 4.23959 -0.0930538 0.0169642 0.000320463 -0.000535179 0.00222136 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.72526e-07 -0.00428995 4 -4.76571e-06 3.99998 +EDGE_SE3:QUAT 393 394 4.20446 -0.0885982 0.00576651 0.000805962 0.00166307 0.00503267 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 5.66742e-06 0.0132555 3.99999 3.33682e-05 3.99994 +EDGE_SE3:QUAT 394 395 4.28205 -0.0742068 0.0194724 0.00182864 -0.00238447 0.005314 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.68518e-05 -0.0191919 3.99998 -5.08464e-05 3.99998 +EDGE_SE3:QUAT 395 396 4.22634 -0.0688436 0.0177863 -0.0012222 -0.000972281 0.00400293 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.79508e-06 -0.00771936 4 -1.54383e-05 3.99995 +EDGE_SE3:QUAT 396 397 4.23106 -0.0655581 0.00359356 -0.00238662 -0.00315808 0.00355647 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.08355e-05 -0.025163 3.99996 -4.52573e-05 4.00011 +EDGE_SE3:QUAT 397 398 4.15847 -0.0876229 0.00334735 0.000596614 0.014241 0.00279652 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00324 4.76948e-05 0.113988 3.99919 0.00016262 4.00321 +EDGE_SE3:QUAT 398 399 4.07239 -0.122676 0.0151702 -3.9413e-05 -0.0035785 -0.0080529 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -1.91103e-06 -0.0286303 3.99995 0.000115283 3.99995 +EDGE_SE3:QUAT 399 400 4.1874 -0.120019 0.0174272 -0.000275047 -0.00135952 -0.0103996 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.03824e-06 -0.0109088 3.99999 5.67685e-05 3.9996 +EDGE_SE3:QUAT 400 401 4.03642 -0.127346 0.0202918 -0.00118007 8.07782e-05 -0.00776453 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.95664e-07 0.000536218 4 -1.93952e-06 3.99976 +EDGE_SE3:QUAT 401 402 4.31095 0.000923787 0.031234 -0.00151797 -0.00116322 0.0415188 0.999136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 7.45317e-06 -0.00852631 4 -0.000171646 3.99312 +EDGE_SE3:QUAT 402 403 4.27387 0.369932 -0.00172259 0.00311854 0.00111882 0.129846 0.991529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.69437e-06 0.00392053 4 0.000144458 3.93256 +EDGE_SE3:QUAT 403 404 4.3725 0.585583 3.91547e-05 -0.00213339 -0.00114064 0.166092 0.986107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.1765e-06 -0.00457621 4 -0.000251732 3.88966 +EDGE_SE3:QUAT 404 405 3.98603 0.482117 0.018511 0.00304007 -0.00430059 0.160183 0.987073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 2.5906e-05 -0.0388357 3.99991 -0.00322939 3.89774 +EDGE_SE3:QUAT 405 406 4.04052 0.509816 0.0010284 0.00271689 -0.00319578 0.159391 0.987207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 7.9393e-06 -0.029708 3.99994 -0.00247867 3.8986 +EDGE_SE3:QUAT 406 407 4.15268 0.500755 -0.0119754 -0.00353617 0.0143763 0.127106 0.991779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00341 0.000448525 0.117659 3.99918 0.00753072 3.93883 +EDGE_SE3:QUAT 407 408 4.34037 0.161007 0.0421799 -0.00440671 0.00409717 0.0435583 0.999033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -5.92693e-05 0.034986 3.99992 0.000776181 3.99272 +EDGE_SE3:QUAT 408 409 4.36074 -0.0943457 0.0372289 -0.00377281 -0.00647531 -0.0040928 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 9.40963e-05 -0.0519931 3.99983 0.000102752 4.00061 +EDGE_SE3:QUAT 409 410 4.40172 -0.154711 0.0262989 0.0026199 -0.00461042 -0.0138108 0.999891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -5.44672e-05 -0.0364409 3.99992 0.000251983 3.99957 +EDGE_SE3:QUAT 410 411 4.39232 -0.136948 -0.000598387 0.000880526 0.000451013 -0.00621881 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.59574e-06 0.0036736 4 -1.14862e-05 3.99985 +EDGE_SE3:QUAT 411 412 4.34485 -0.107257 0.00615729 0.000571022 0.00751862 -0.00306181 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0009 1.30371e-05 0.060181 3.99977 -9.14211e-05 4.00087 +EDGE_SE3:QUAT 412 413 4.16082 -0.0894417 0.0466038 -0.00152523 0.0031566 -0.00254264 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -1.98195e-05 0.0252068 3.99996 -3.23932e-05 4.00013 +EDGE_SE3:QUAT 413 414 4.01131 -0.0904173 0.0192136 -0.00148307 -0.00484606 -0.00265977 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 2.73019e-05 -0.0388185 3.99991 5.082e-05 4.00035 +EDGE_SE3:QUAT 414 415 4.33974 -0.0946825 -0.00442572 -0.00230817 0.00200302 -0.0023164 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.86167e-05 0.0159599 3.99998 -1.86815e-05 4.00004 +EDGE_SE3:QUAT 415 416 4.41435 -0.0987886 -0.000289403 -0.000948946 -0.000800129 -0.00255467 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.01597e-06 -0.00643006 4 8.21107e-06 3.99998 +EDGE_SE3:QUAT 416 417 4.32943 -0.0978798 0.0181224 -0.00360825 -0.000200933 -0.00455329 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.36883e-06 -0.00180454 4 4.25365e-06 3.99992 +EDGE_SE3:QUAT 417 418 4.39594 -0.156638 0.0229942 0.00577775 -0.00070335 -0.0101851 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -1.36293e-05 -0.00491955 4 2.39084e-05 3.99959 +EDGE_SE3:QUAT 418 419 4.02356 -0.102975 0.0187012 0.000339955 -0.00617514 -0.00458787 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -1.25938e-05 -0.0493874 3.99985 0.000113632 4.00053 +EDGE_SE3:QUAT 419 420 4.27406 -0.11939 -0.00933989 0.00544082 0.000171505 0.0080755 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 1.82225e-06 0.000844634 4 2.70241e-06 3.99974 +EDGE_SE3:QUAT 420 421 4.22302 0.13884 -0.00800953 0.00411344 0.0178365 0.0862176 0.996108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00462 0.000898933 0.137002 3.9989 0.00587031 3.97495 +EDGE_SE3:QUAT 421 422 4.12694 0.452748 0.0281802 -0.00258375 -0.00486495 0.146938 0.98913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 0.00010639 -0.0331771 3.99995 -0.00229624 3.91391 +EDGE_SE3:QUAT 422 423 4.19381 0.642694 0.0264779 -0.00575461 -0.00504161 0.181172 0.983422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 0.000120036 -0.0261248 3.99998 -0.00192973 3.86887 +EDGE_SE3:QUAT 423 424 4.09493 0.564378 0.0138985 0.00598833 0.00172537 0.183424 0.983014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -1.26349e-05 0.000226618 4 -0.000403773 3.86542 +EDGE_SE3:QUAT 424 425 4.33889 0.900543 0.0229041 -0.0013567 0.00281559 0.24727 0.968942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.7958e-05 0.0243531 3.99997 0.0030874 3.75558 +EDGE_SE3:QUAT 425 426 4.20202 0.985552 0.00315092 -0.004902 -0.000313977 0.251665 0.967802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -3.41198e-05 0.0119018 3.99998 0.00212765 3.74669 +EDGE_SE3:QUAT 426 427 4.10565 0.741221 0.0124702 0.00301623 -0.00746942 0.205004 0.978728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00096 0.000209412 -0.0632544 3.99978 -0.00660394 3.83289 +EDGE_SE3:QUAT 427 428 4.35178 0.551205 -0.0126135 -0.00153145 -0.00223492 0.137442 0.990506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.3179e-05 -0.0148812 3.99999 -0.000953217 3.92449 +EDGE_SE3:QUAT 428 429 4.13523 0.283344 -0.0191612 -0.00280929 0.0184485 0.0842206 0.996272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00551 0.000490075 0.149027 3.99865 0.00629272 3.97717 +EDGE_SE3:QUAT 429 430 4.4334 0.109151 0.0291469 -0.00251626 0.00199549 0.0321621 0.999478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.83074e-05 0.0169098 3.99998 0.000276748 3.99593 +EDGE_SE3:QUAT 430 431 4.17554 -0.0461046 0.0273408 -0.00356627 -0.00673665 0.00540026 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 0.000101445 -0.0536671 3.99982 -0.000148625 4.0006 +EDGE_SE3:QUAT 431 432 4.27252 -0.0600225 -0.011445 -0.00160083 -0.0012888 0.0045471 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 8.33806e-06 -0.0102227 3.99999 -2.32388e-05 3.99994 +EDGE_SE3:QUAT 432 433 4.37387 -0.0787072 0.0151967 0.000239705 -0.00873841 0.00494246 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 6.74132e-07 -0.0699376 3.99969 -0.000172541 4.00112 +EDGE_SE3:QUAT 433 434 4.42959 -0.0730096 0.00914638 0.00457225 0.00830244 0.00418175 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 0.00015816 0.066202 3.99973 0.000145883 4.00103 +EDGE_SE3:QUAT 434 435 4.3047 -0.0839115 0.0312165 0.00101844 0.000231263 0.00323368 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.19267e-07 0.00181055 4 2.90732e-06 3.99996 +EDGE_SE3:QUAT 435 436 4.19742 -0.0907578 0.0230562 0.000781962 -0.00198647 0.0035396 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -5.89457e-06 -0.0159249 3.99998 -2.81302e-05 4.00001 +EDGE_SE3:QUAT 436 437 4.22753 -0.0848961 -0.0147568 -0.000159602 0.00128961 0.00276902 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -7.13254e-07 0.0103221 3.99999 1.42873e-05 4 +EDGE_SE3:QUAT 437 438 4.22115 -0.0753146 0.00908493 -0.00191261 0.00782414 0.00267782 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00097 -5.60452e-05 0.062667 3.99975 8.11713e-05 4.00095 +EDGE_SE3:QUAT 438 439 4.29272 -0.0941986 0.0386378 0.000489463 -0.000397308 0.00200354 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.7407e-07 -0.00319021 4 -3.19792e-06 3.99999 +EDGE_SE3:QUAT 439 440 4.07415 -0.0666012 0.0232788 -0.00154299 -0.00552261 0.00585378 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 3.82545e-05 -0.0440747 3.99988 -0.00013006 4.00035 +EDGE_SE3:QUAT 440 441 4.06348 -0.0586851 0.0166169 0.00155329 -0.00730974 0.00197714 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00085 -4.29497e-05 -0.0585252 3.99979 -5.59062e-05 4.00084 +EDGE_SE3:QUAT 441 442 4.23328 -0.14636 -0.010568 0.00193154 0.00213577 -0.0226844 0.999739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.45608e-05 0.0175988 3.99998 -0.000201335 3.99802 +EDGE_SE3:QUAT 442 443 4.02614 -0.241154 0.0183384 -0.000165177 0.0180832 -0.0549833 0.998323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00518 -0.000441208 0.144064 3.99873 -0.00396838 3.99309 +EDGE_SE3:QUAT 443 444 4.18417 -0.484396 0.0247426 -0.00526001 -0.00330043 -0.126653 0.991928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 4.58003e-05 -0.0336807 3.99992 0.00228632 3.93612 +EDGE_SE3:QUAT 444 445 4.09688 -0.755028 0.0140666 0.00290832 -0.000732314 -0.179505 0.983753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.96531e-06 0.000552498 4 -0.000245592 3.87111 +EDGE_SE3:QUAT 445 446 4.16756 -1.01479 0.00771215 0.000342031 0.0029793 -0.242065 0.970255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -4.54789e-05 0.0227258 3.99998 -0.0027025 3.76575 +EDGE_SE3:QUAT 398 445 5.71949 4.11085 0.0439766 0.00412282 0.00687039 -0.919117 0.393902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.000189584 0.0232195 4.00056 0.00644501 0.62082 +EDGE_SE3:QUAT 399 445 1.57302 4.25036 0.0212081 0.000732274 0.00813383 -0.916057 0.400965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 3.80843e-05 0.00774052 4.00011 0.0182512 0.643233 +EDGE_SE3:QUAT 400 445 -2.7372 4.32481 0.0102369 -0.000391198 0.0093156 -0.911877 0.410358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000101838 0.00324248 3.99999 0.0236048 0.673776 +EDGE_SE3:QUAT 446 447 4.02795 -1.10008 -0.0281904 0.00107177 0.0142218 -0.262849 0.964732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00276 -0.00111864 0.105477 3.99956 -0.0134907 3.72641 +EDGE_SE3:QUAT 397 446 6.25863 1.70862 -0.0467127 -0.00882493 0.0115182 -0.986685 0.161994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000376839 -0.0362797 3.99997 0.054222 0.106055 +EDGE_SE3:QUAT 398 446 2.08867 1.79302 0.00906564 0.00518326 0.00854739 -0.98717 0.15936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 9.17359e-05 0.0217841 4.00049 0.0256031 0.101875 +EDGE_SE3:QUAT 399 446 -1.96571 1.87418 0.0098742 0.00181914 0.0088773 -0.985913 0.167016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000116221 0.00790628 3.99992 0.0306954 0.111837 +EDGE_SE3:QUAT 400 446 -6.2144 1.87928 0.0162288 0.00022828 0.00973387 -0.984094 0.177383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000120012 0.00139085 3.99973 0.0355923 0.126188 +EDGE_SE3:QUAT 447 448 4.08019 -1.14044 0.00141398 0.00263449 0.00340882 -0.262407 0.964948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -5.48729e-05 0.0324196 3.99994 -0.00448556 3.72483 +EDGE_SE3:QUAT 396 447 6.33201 1.41277 0.0299778 -0.00604784 -0.00731852 0.995009 0.099331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000194348 0.024492 4.00016 0.0333168 0.0398976 +EDGE_SE3:QUAT 397 447 2.09901 1.47277 0.0128208 -0.00271123 -0.00975934 0.994606 0.10323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.09238e-05 0.0109319 3.99964 0.0402148 0.0430642 +EDGE_SE3:QUAT 398 447 -2.02621 1.56996 -0.0550235 -0.0171099 -0.0105011 0.994168 0.105956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9992 0.00123399 0.0695047 4.00323 0.0552438 0.0468942 +EDGE_SE3:QUAT 399 447 -6.10022 1.59521 -0.0202752 -0.0136569 -0.0102788 0.995026 0.0981381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000829095 0.0553481 4.00186 0.0507878 0.0399458 +EDGE_SE3:QUAT 448 449 4.18256 -1.02625 0.0102465 0.000117742 0.000371622 -0.233354 0.972392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.46966e-07 0.00305121 4 -0.000358976 3.78219 +EDGE_SE3:QUAT 396 448 2.562 3.34131 0.00742082 -0.00691539 -0.00575782 0.934071 0.356974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 0.000150229 0.0303323 3.99995 0.0332639 0.510269 +EDGE_SE3:QUAT 397 448 -1.66172 3.41496 0.0216689 -0.00333905 -0.00706176 0.932686 0.360604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.64006e-05 0.0130481 3.99978 0.0278733 0.520409 +EDGE_SE3:QUAT 398 448 -5.75328 3.56014 -0.152737 -0.0168438 -0.0119348 0.931585 0.362937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 0.00104828 0.0748042 4.00016 0.0752499 0.52993 +EDGE_SE3:QUAT 449 450 3.94197 -0.83005 -0.00407587 0.00338911 -0.0129465 -0.163424 0.986465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00211 -0.000715418 -0.092961 3.99957 0.0073235 3.89532 +EDGE_SE3:QUAT 396 449 0.13536 6.88326 0.00120213 -0.00583242 -0.00672531 0.824968 0.565109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000123435 0.0218298 3.99976 0.0259632 1.27778 +EDGE_SE3:QUAT 450 451 4.18376 -0.341491 0.0161359 0.000521438 -0.0125194 -0.0461651 0.998855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00248 -0.000198289 -0.0996005 3.99939 0.00230006 3.99395 +EDGE_SE3:QUAT 451 452 4.32447 -0.171876 -0.0268902 0.00532907 0.00611893 -0.00557495 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 0.000126687 0.0493102 3.99985 -0.000132989 4.00048 +EDGE_SE3:QUAT 452 453 4.23844 -0.0550637 0.00573537 -0.00579293 0.000100576 0.00288209 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -3.10305e-06 0.0010049 4 1.54231e-06 3.99997 +EDGE_SE3:QUAT 453 454 4.32124 -0.0891427 0.00982075 0.00215153 -0.00154376 0.00228677 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.32389e-05 -0.0124091 3.99999 -1.40871e-05 4.00002 +EDGE_SE3:QUAT 454 455 4.21689 -0.0692608 -0.0147282 -0.00278188 -0.00366823 0.0020021 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 4.13453e-05 -0.0292798 3.99995 -3.01874e-05 4.0002 +EDGE_SE3:QUAT 455 456 4.08519 -0.0835792 -0.0430681 0.00131861 0.00297195 0.00221168 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.61141e-05 0.0237411 3.99996 2.65222e-05 4.00012 +EDGE_SE3:QUAT 456 457 4.43358 -0.0814892 -0.0209707 0.00172168 0.0034251 0.00306836 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 2.4379e-05 0.027338 3.99995 4.23969e-05 4.00015 +EDGE_SE3:QUAT 457 458 4.55818 -0.080389 0.0232291 -0.000875433 0.00467793 0.00305198 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -1.47991e-05 0.0374578 3.99991 5.67291e-05 4.00031 +EDGE_SE3:QUAT 458 459 4.10044 -0.0739748 0.00323373 -0.000496012 -0.00787257 0.00295213 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00099 2.00175e-05 -0.0629758 3.99975 -9.37453e-05 4.00096 +EDGE_SE3:QUAT 459 460 4.16133 -0.0795181 -0.0313967 0.000534729 -0.00160221 0.00296406 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.2508e-06 -0.0128367 3.99999 -1.90011e-05 4.00001 +EDGE_SE3:QUAT 460 461 4.0824 -0.0852266 -0.00280018 0.000593747 0.00719034 0.00402183 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 2.2065e-05 0.057503 3.99979 0.000116413 4.00076 +EDGE_SE3:QUAT 461 462 4.53269 -0.0786386 0.050019 -0.00261295 0.00500904 0.00143934 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 -5.15813e-05 0.0401205 3.9999 2.73154e-05 4.00039 +EDGE_SE3:QUAT 462 463 4.24424 -0.148671 0.069171 -0.000914046 -0.00206466 -0.014682 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 6.11972e-06 -0.0166732 3.99998 0.00012269 3.99921 +EDGE_SE3:QUAT 463 464 4.2299 -0.244497 0.0378877 -0.000443893 0.00610922 -0.054348 0.998503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 -5.8684e-05 0.0483746 3.99986 -0.00131084 3.98877 +EDGE_SE3:QUAT 464 465 4.07508 -0.422537 -0.0562471 -0.00947746 0.02246 -0.0994059 0.994748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00651 -0.00183842 0.166001 3.99845 -0.00816073 3.96734 +EDGE_SE3:QUAT 465 466 3.98255 -0.580048 0.0110731 0.00219337 0.002915 -0.1464 0.989219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -6.59937e-06 0.0263735 3.99996 -0.0020056 3.91444 +EDGE_SE3:QUAT 466 467 4.1747 -0.909851 0.0103457 0.000795359 -0.00175571 -0.22342 0.97472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.55042e-05 -0.0109459 4 0.0011029 3.80036 +EDGE_SE3:QUAT 467 468 3.8736 -1.04043 -0.0366229 0.00416605 0.0157247 -0.255633 0.966637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00389 -0.00130855 0.126004 3.99929 -0.0161169 3.74257 +EDGE_SE3:QUAT 468 469 3.9363 -1.1279 0.000815407 -0.00486597 0.00511966 -0.272484 0.962134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -0.000103741 0.0213567 4 -0.0019719 3.70311 +EDGE_SE3:QUAT 469 470 4.00603 -1.21676 -0.00567968 0.00346466 -0.000554677 -0.272596 0.962122 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.67285e-05 0.00681986 3.99999 -0.00146668 3.70277 +EDGE_SE3:QUAT 470 471 3.96474 -0.950938 -0.00955231 0.00624163 0.00413692 -0.188218 0.982099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 2.39581e-05 0.0451205 3.99986 -0.00462839 3.8588 +EDGE_SE3:QUAT 471 472 4.33847 -0.506528 -0.0661997 -0.00120748 0.0104929 -0.0775847 0.99693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00168 -0.000247873 0.082096 3.9996 -0.00316701 3.97761 +EDGE_SE3:QUAT 472 473 4.24634 -0.174726 -0.0109801 -0.000982057 -0.000258769 -0.0169333 0.999856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.11512e-06 -0.00226878 4 1.97677e-05 3.99885 +EDGE_SE3:QUAT 473 474 4.45693 -0.105651 0.0241347 -0.00336041 0.00441215 -0.00387827 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -6.07685e-05 0.0351418 3.99992 -6.96157e-05 4.00025 +EDGE_SE3:QUAT 474 475 4.51637 -0.0987971 0.0517747 0.00273518 -0.00554833 0.00415231 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -5.78919e-05 -0.0445261 3.99988 -9.05357e-05 4.00043 +EDGE_SE3:QUAT 475 476 4.52669 -0.0518123 0.0378529 0.000257561 -0.00598918 0.0113229 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 3.58041e-06 -0.0479453 3.99986 -0.00027137 4.00006 +EDGE_SE3:QUAT 476 477 4.45401 -0.0516658 -0.0128846 0.00269756 -0.00475118 0.0127988 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -4.49599e-05 -0.038417 3.99991 -0.000245283 3.99971 +EDGE_SE3:QUAT 477 478 4.32208 -0.0482687 -0.024375 0.00170011 0.00518041 0.0126248 0.999905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 4.29903e-05 0.0411795 3.99989 0.000260534 3.99979 +EDGE_SE3:QUAT 478 479 4.45542 -0.038383 0.00232631 -0.00141004 0.0124393 0.0124345 0.999844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00248 -2.41372e-05 0.0997554 3.99938 0.000616346 4.00187 +EDGE_SE3:QUAT 479 480 4.13602 -0.0495823 0.048323 -0.00112857 -0.000694154 0.00529344 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.13948e-06 -0.00548131 4 -1.44569e-05 3.9999 +EDGE_SE3:QUAT 480 481 4.02722 -0.0967948 0.0281506 -0.00161102 -0.00586067 -0.00479502 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00054 3.39171e-05 -0.0469819 3.99986 0.000111421 4.00046 +EDGE_SE3:QUAT 481 482 4.31183 -0.128644 -0.0170788 -0.00174645 -0.00316652 -0.00880145 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 2.01931e-05 -0.0255145 3.99996 0.000112135 3.99985 +EDGE_SE3:QUAT 482 483 4.29015 -0.114983 0.0052864 0.00126388 0.00471248 -0.00331626 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 2.2102e-05 0.0377523 3.99991 -6.19653e-05 4.00031 +EDGE_SE3:QUAT 483 484 4.2455 -0.0914985 0.0453003 0.00378601 -0.00172121 0.00121957 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.61189e-05 -0.0138249 3.99999 -8.17081e-06 4.00004 +EDGE_SE3:QUAT 484 485 4.16435 -0.0772237 0.0337502 -0.000468299 0.00354945 0.00615736 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -4.795e-06 0.0284298 3.99995 8.74299e-05 4.00005 +EDGE_SE3:QUAT 485 486 4.19386 -0.00697508 -0.0143336 -0.00136878 0.0019237 0.0257657 0.999665 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -8.52064e-06 0.0157974 3.99998 0.000205149 3.99741 +EDGE_SE3:QUAT 486 487 4.07776 0.185928 0.0189322 0.0034381 -0.00263136 0.102659 0.994707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.26723e-05 -0.0249252 3.99996 -0.00134548 3.958 +EDGE_SE3:QUAT 487 488 4.1788 0.713111 0.0282666 0.00207874 0.000863866 0.211406 0.977396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.09702e-07 0.00133643 4 -6.12259e-05 3.82123 +EDGE_SE3:QUAT 488 489 4.07306 0.851073 0.0125876 -0.00260961 -0.00495666 0.24001 0.970754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 0.000123874 -0.0290499 3.99998 -0.00304458 3.76979 +EDGE_SE3:QUAT 489 490 4.07894 0.891547 0.0139654 -0.00184057 0.000186536 0.238121 0.971234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.8658e-06 0.00642773 4 0.000968398 3.7732 +EDGE_SE3:QUAT 490 491 4.37609 0.687576 -0.0020034 -0.000906567 0.00757512 0.165814 0.986127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00089 0.000200306 0.0599015 3.9998 0.0049474 3.89092 +EDGE_SE3:QUAT 491 492 4.3812 0.480296 0.0270968 -0.00078676 -0.00274601 0.13563 0.990755 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 2.92522e-05 -0.0201003 3.99998 -0.0013205 3.92652 +EDGE_SE3:QUAT 492 493 4.07212 0.431889 0.0185558 0.00273916 -0.00461084 0.137841 0.99044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 2.48612e-05 -0.0403173 3.9999 -0.00285734 3.92441 +EDGE_SE3:QUAT 493 494 4.02087 0.462257 0.015992 0.00313082 -0.00133633 0.144248 0.989536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.5594e-05 -0.0157029 3.99998 -0.00125445 3.91683 +EDGE_SE3:QUAT 494 495 4.04678 0.399312 0.0246863 -0.00391355 0.00800177 0.109019 0.994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00109 4.94513e-05 0.0679721 3.99971 0.00377328 3.95361 +EDGE_SE3:QUAT 495 496 4.17546 0.168214 -0.0184847 -0.00335746 -0.000551404 0.0506063 0.998713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.95886e-06 -0.00235881 4 -4.23548e-05 3.98976 +EDGE_SE3:QUAT 496 497 4.33287 0.0393592 -0.0132114 -0.00390791 -0.00340569 0.0229977 0.999722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 5.63852e-05 -0.0261461 3.99996 -0.000297487 3.99806 +EDGE_SE3:QUAT 497 498 4.04169 -0.0395908 0.0181111 -0.000961538 0.000319892 0.0106252 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.28059e-06 0.00268129 4 1.44584e-05 3.99955 +EDGE_SE3:QUAT 498 499 4.55396 -0.0518129 0.0294279 0.0011004 0.00105459 0.00489125 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.72333e-06 0.00837181 4 2.04507e-05 3.99992 +EDGE_SE3:QUAT 499 500 4.22087 -0.0688585 0.0143786 0.0019965 -0.00414209 0.00327257 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -3.18375e-05 -0.0332164 3.99993 -5.35785e-05 4.00023 +EDGE_SE3:QUAT 500 501 4.19757 -0.079864 -0.0117325 -0.000629738 -0.000357268 -0.000623855 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.00004e-07 -0.00286286 4 8.91561e-07 4 +EDGE_SE3:QUAT 501 502 4.49747 -0.0896452 -0.011149 -0.000552457 0.01044 -0.000671106 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00174 -2.48605e-05 0.0835476 3.99956 -2.9512e-05 4.00174 +EDGE_SE3:QUAT 502 503 4.36376 -0.0966078 0.0307278 -0.00139928 0.00791413 -0.00230912 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00099 -4.77672e-05 0.0632874 3.99975 -7.5204e-05 4.00098 +EDGE_SE3:QUAT 503 504 4.32184 -0.094959 0.0489418 -0.00220257 -0.00544755 -0.00286414 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 4.60788e-05 -0.0436598 3.99988 6.10061e-05 4.00044 +EDGE_SE3:QUAT 504 505 4.07178 -0.0996924 0.0219844 0.00014316 -0.0059665 -0.00287504 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 -5.8742e-06 -0.0477324 3.99986 6.87616e-05 4.00054 +EDGE_SE3:QUAT 505 506 4.54923 -0.101783 0.000914602 -0.000433115 -0.00738897 -0.0023966 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00087 9.67218e-06 -0.059135 3.99978 7.03389e-05 4.00085 +EDGE_SE3:QUAT 506 507 4.33471 -0.110987 -0.00282073 0.00278189 0.00650547 -0.00106415 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 7.14154e-05 0.0520863 3.99983 -2.49032e-05 4.00067 +EDGE_SE3:QUAT 507 508 4.25738 -0.10858 0.0434324 0.00318073 -0.00293708 0.00156582 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -3.71731e-05 -0.0235567 3.99997 -1.77988e-05 4.00013 +EDGE_SE3:QUAT 508 509 4.2028 -0.0103298 0.0393408 0.0023325 0.00833284 0.0286136 0.999553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 0.000123186 0.0657953 3.99973 0.000941593 3.99781 +EDGE_SE3:QUAT 509 510 4.10101 0.177677 -0.00529079 0.00222965 0.00156002 0.0815857 0.996663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.40008e-05 0.0101825 3.99999 0.000384092 3.9734 +EDGE_SE3:QUAT 510 511 4.16465 0.383715 0.0121875 0.000670315 -0.00441013 0.122475 0.992462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 4.6166e-05 -0.035468 3.99993 -0.00217582 3.94031 +EDGE_SE3:QUAT 511 512 4.13181 0.51677 0.00390494 0.00143164 0.00239505 0.162449 0.986713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.7018e-05 0.0156654 3.99999 0.00117614 3.8945 +EDGE_SE3:QUAT 512 513 4.276 0.600027 0.002827 -0.0017458 0.00399551 0.166458 0.986039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 4.1129e-05 0.0340698 3.99993 0.00289445 3.88946 +EDGE_SE3:QUAT 513 514 4.32721 0.545005 0.00113667 -0.00352659 -0.00187585 0.136534 0.990627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.74005e-05 -0.00888271 4 -0.0004654 3.92545 +EDGE_SE3:QUAT 514 515 4.46139 0.337515 0.0124009 -0.00247581 -0.00215154 0.0839595 0.996464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.41422e-05 -0.0145479 3.99999 -0.000573489 3.97186 +EDGE_SE3:QUAT 515 516 4.46621 0.0325005 0.0199354 0.00238753 -0.00206597 0.0193521 0.999808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.85131e-05 -0.0170729 3.99998 -0.000166706 3.99857 +EDGE_SE3:QUAT 469 515 0.566432 6.73581 0.17147 0.00815123 0.0140813 -0.953661 0.300442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 -0.000254938 0.0397576 4.00191 0.0262145 0.361725 +EDGE_SE3:QUAT 516 517 4.40351 -0.101279 0.0237316 -0.00372518 0.00682571 -0.00559964 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -0.00010736 0.0543604 3.99982 -0.000156173 4.00061 +EDGE_SE3:QUAT 468 516 3.52776 4.05573 0.0680535 0.00343668 0.00686668 -0.998791 0.048556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 9.52723e-05 0.0138022 4.00006 0.0259747 0.00964759 +EDGE_SE3:QUAT 469 516 -3.07427 4.17004 0.0837989 0.00742417 0.011293 -0.947642 0.319047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 -0.000317742 0.0368016 4.00155 0.0170803 0.407651 +EDGE_SE3:QUAT 517 518 4.56662 -0.138343 -0.0243947 0.00271204 0.0040436 -0.0109368 0.999928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 4.01434e-05 0.0327005 3.99993 -0.000178406 3.99979 +EDGE_SE3:QUAT 467 517 4.99856 2.61126 0.0343743 0.00289346 -0.0118726 0.976638 0.214543 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000194222 -0.013284 4.00007 0.0373812 0.184536 +EDGE_SE3:QUAT 468 517 -0.86052 3.73423 0.0647978 0.00997592 0.0111068 -0.998965 0.0429597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.000370507 0.0400238 4.00133 0.0408222 0.00820073 +EDGE_SE3:QUAT 469 517 -6.59316 1.63401 0.0191616 0.0126613 0.0170785 -0.949442 0.313223 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99882 -0.000930809 0.0617046 4.00421 0.0235494 0.393702 +EDGE_SE3:QUAT 518 519 4.01593 -0.122944 0.00873894 0.00100044 -0.00229838 -0.0100512 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.03769e-05 -0.0182639 3.99998 9.17102e-05 3.99968 +EDGE_SE3:QUAT 467 518 0.971796 4.63844 0.0651227 -0.000279077 -0.00816408 0.974261 0.225276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.08048e-05 0.000450706 3.99981 0.0290645 0.203222 +EDGE_SE3:QUAT 468 518 -5.33816 3.50055 -0.0580588 0.0142459 0.0082906 -0.999341 0.0323499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 0.00032619 0.057072 4.00315 0.029425 0.00521789 +EDGE_SE3:QUAT 519 520 4.15362 -0.116721 0.0168352 0.000640285 0.000992959 -0.00852277 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.36648e-06 0.00800831 4 -3.42033e-05 3.99973 +EDGE_SE3:QUAT 467 519 -2.50974 6.47242 0.0917687 0.00240847 -0.0075006 0.971855 0.23545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -6.23914e-05 -0.0111843 4.00013 0.0216424 0.221909 +EDGE_SE3:QUAT 520 521 4.08679 -0.107517 0.0139218 -0.00277823 -0.00221638 -0.00806834 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.41531e-05 -0.0179984 3.99998 7.26362e-05 3.99982 +EDGE_SE3:QUAT 521 522 4.09691 -0.117368 0.0313074 -0.000798583 0.00499343 -0.00537049 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -1.91355e-05 0.0398977 3.9999 -0.000107592 4.00028 +EDGE_SE3:QUAT 522 523 4.2702 -0.112049 0.0197237 0.00135431 -0.00375208 -0.0030167 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -2.13019e-05 -0.0299686 3.99994 4.56414e-05 4.00019 +EDGE_SE3:QUAT 523 524 4.21113 -0.0975689 0.019109 0.000326982 -0.00101031 -0.00166175 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.36066e-06 -0.00807599 4 6.7164e-06 4.00001 +EDGE_SE3:QUAT 524 525 4.10624 -0.0941487 0.0314939 7.8119e-05 0.000270045 0.000681374 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.55412e-08 0.00215972 4 7.35852e-07 4 +EDGE_SE3:QUAT 525 526 4.50211 -0.0666779 0.0339388 -0.00390662 0.00267239 0.00212381 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -4.16552e-05 0.0214786 3.99997 2.21705e-05 4.0001 +EDGE_SE3:QUAT 526 527 4.27042 -0.0838782 -0.0106002 3.33869e-05 0.0064116 0.00327641 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 4.08967e-06 0.051298 3.99984 8.41047e-05 4.00061 +EDGE_SE3:QUAT 527 528 4.26718 -0.0535459 0.020125 0.00117745 -0.0015353 0.00841548 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -6.84028e-06 -0.0124 3.99999 -5.22748e-05 3.99976 +EDGE_SE3:QUAT 528 529 4.29593 -0.00277841 0.0197716 1.41743e-05 -0.00183303 0.0200145 0.999798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.50951e-06 -0.014659 3.99999 -0.000146682 3.99845 +EDGE_SE3:QUAT 529 530 4.15251 -0.0229896 0.0188806 -0.000163647 -0.00426929 0.0256519 0.999662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 1.39692e-05 -0.0340724 3.99993 -0.000436807 3.99766 +EDGE_SE3:QUAT 530 531 4.17012 0.190171 0.00264575 0.00442171 0.00503086 0.0866633 0.996215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 0.000117209 0.0352199 3.99993 0.00145566 3.97027 +EDGE_SE3:QUAT 531 532 4.17599 0.454139 0.0163361 -0.00470732 -0.00209503 0.134426 0.99091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.00342e-05 -0.00880556 4 -0.000411631 3.92774 +EDGE_SE3:QUAT 532 533 4.1119 0.503079 0.013536 0.00464251 -0.00251949 0.157784 0.98746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.98614e-05 -0.0280528 3.99995 -0.00242305 3.90061 +EDGE_SE3:QUAT 533 534 4.26615 0.661707 0.0175654 0.00160293 -0.00130663 0.17642 0.984313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -6.40805e-07 -0.013292 3.99999 -0.00125746 3.87555 +EDGE_SE3:QUAT 534 535 4.33601 0.602005 0.018217 -0.00387102 0.00962649 0.138714 0.990278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00159 0.000178381 0.0811898 3.99961 0.00572441 3.92468 +EDGE_SE3:QUAT 535 536 4.62202 0.285723 0.00554979 -0.0074072 -0.00248222 0.0587709 0.998241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 5.27294e-05 -0.0145417 3.99999 -0.000375826 3.98624 +EDGE_SE3:QUAT 536 537 4.09617 -0.0211368 -0.0152654 -0.000114523 -0.00194685 0.011991 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.97908e-06 -0.0155552 3.99998 -9.32357e-05 3.99949 +EDGE_SE3:QUAT 537 538 4.16211 -0.051905 -0.0119379 -0.00176199 0.00797273 0.00311062 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -5.15632e-05 0.0638607 3.99975 9.67298e-05 4.00098 +EDGE_SE3:QUAT 538 539 4.28638 -0.0785964 0.0260564 -0.00030006 -0.00805741 0.000149412 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00104 9.91238e-06 -0.0644734 3.99974 -5.28749e-06 4.00104 +EDGE_SE3:QUAT 539 540 4.29041 -0.0999438 0.0309541 0.00212411 -0.00178857 -0.000659219 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.52238e-05 -0.0142918 3.99999 4.87181e-06 4.00005 +EDGE_SE3:QUAT 540 541 4.20645 -0.105389 -0.00576796 0.00153207 -0.0044377 -0.00188172 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -2.80553e-05 -0.0354691 3.99992 3.40905e-05 4.0003 +EDGE_SE3:QUAT 541 542 4.26037 -0.105103 -0.0218791 0.000153714 0.00106134 -0.00395906 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 5.46141e-07 0.00849789 4 -1.68226e-05 3.99996 +EDGE_SE3:QUAT 542 543 4.22128 -0.117843 -0.000672641 0.00404427 0.0154687 -0.00472046 0.999861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00378 0.000224464 0.124076 3.99904 -0.000270442 4.00376 +EDGE_SE3:QUAT 543 544 4.25249 -0.109828 0.0312933 -0.000837155 -0.00101618 -0.00477442 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.31007e-06 -0.00817718 4 1.95379e-05 3.99993 +EDGE_SE3:QUAT 544 545 4.25722 -0.102632 0.0189491 -0.00300585 -0.00550948 -0.00510168 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 6.28941e-05 -0.0442623 3.99988 0.000110893 4.00039 +EDGE_SE3:QUAT 545 546 4.28887 -0.111984 -0.0177924 -0.00024622 5.90858e-05 -0.0059407 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.57766e-08 0.000455109 4 -1.33445e-06 3.99986 +EDGE_SE3:QUAT 546 547 4.05725 -0.114219 0.0122398 -0.0010676 -0.0031118 -0.00724241 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.16622e-05 -0.024986 3.99996 9.03488e-05 3.99995 +EDGE_SE3:QUAT 547 548 4.43015 -0.133706 0.034428 0.00624863 0.00517906 0.000748901 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 0.000129733 0.0413777 3.99989 1.95052e-05 4.00043 +EDGE_SE3:QUAT 548 549 4.0923 0.041027 0.0563367 0.00352942 3.19027e-06 0.0477397 0.998854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -4.6653e-06 -0.0019934 4 -6.36674e-05 3.99088 +EDGE_SE3:QUAT 549 550 4.16414 0.250227 -0.00389938 -0.000743275 0.00631517 0.0949442 0.995462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 7.28908e-05 0.0506886 3.99984 0.00240912 3.96458 +EDGE_SE3:QUAT 550 551 4.40662 0.53739 0.025895 -0.00359016 -0.00470178 0.161918 0.986786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 0.000107014 -0.0292913 3.99996 -0.00214422 3.89534 +EDGE_SE3:QUAT 551 552 4.15605 0.70258 0.0357281 -0.000836143 -0.000161954 0.204243 0.97892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.17592e-07 0.000776909 4 0.000151883 3.83314 +EDGE_SE3:QUAT 552 553 4.25571 0.971517 0.00298036 0.0033609 -0.00252756 0.263692 0.964598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.99839e-05 -0.0282916 3.99995 -0.00409827 3.72206 +EDGE_SE3:QUAT 553 554 3.98534 0.92272 -0.00511416 -0.00448064 0.0047066 0.248508 0.968608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 8.21587e-05 0.0470363 3.99987 0.00624393 3.75353 +EDGE_SE3:QUAT 554 555 3.98685 0.862835 0.00948669 0.00443204 -0.00556104 0.241429 0.970392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 0.00012012 -0.0530051 3.99984 -0.00674909 3.76755 +EDGE_SE3:QUAT 555 556 4.07604 0.805784 -0.00631121 0.00166396 -0.00241431 0.210607 0.977566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 1.81756e-05 -0.0221253 3.99997 -0.0024306 3.8227 +EDGE_SE3:QUAT 556 557 4.38643 0.49509 -0.0135667 -0.00452914 0.0211587 0.109345 0.993768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00734 0.000821547 0.172418 3.99822 0.00947448 3.95959 +EDGE_SE3:QUAT 557 558 4.27171 0.0539147 0.0340261 -0.00371746 -0.00063097 0.0204987 0.999783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.2529e-06 -0.0041303 4 -3.92239e-05 3.99832 +EDGE_SE3:QUAT 558 559 4.02702 -0.103039 0.00921656 -0.00221065 -0.00995547 -0.0068865 0.999924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 7.19697e-05 -0.0798481 3.9996 0.000270147 4.0014 +EDGE_SE3:QUAT 559 560 4.0859 -0.118488 0.00186011 0.00211739 -0.0028458 -0.0081538 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.53718e-05 -0.0225574 3.99997 9.20929e-05 3.99986 +EDGE_SE3:QUAT 560 561 4.19832 -0.130725 0.0221422 -0.000246323 0.00556985 -0.0099677 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -1.2898e-05 0.0445275 3.99988 -0.000222114 4.0001 +EDGE_SE3:QUAT 561 562 4.31871 -0.136435 0.0438802 0.00198894 0.000328618 -0.0106501 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.91891e-06 0.00288265 4 -1.57947e-05 3.99955 +EDGE_SE3:QUAT 562 563 4.30734 -0.131708 0.0202374 0.00217329 -0.00443412 -0.00702002 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -4.15735e-05 -0.0352894 3.99992 0.000124691 4.00011 +EDGE_SE3:QUAT 563 564 4.35722 -0.0957348 -0.0440722 -0.00178461 0.0028473 -0.000608892 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.04303e-05 0.0227659 3.99997 -7.27717e-06 4.00013 +EDGE_SE3:QUAT 564 565 4.47264 -0.0864903 -0.0209663 -0.00259309 0.0067825 0.00250355 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 -6.77581e-05 0.0543456 3.99982 6.52235e-05 4.00071 +EDGE_SE3:QUAT 565 566 4.33423 -0.0645916 0.0310897 -0.00118629 0.00477958 0.00508403 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -1.99474e-05 0.0383105 3.99991 9.6817e-05 4.00026 +EDGE_SE3:QUAT 566 567 4.32741 -0.0569625 0.038884 -0.0015086 -0.00760291 0.00598758 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00091 5.40886e-05 -0.0607236 3.99977 -0.00018388 4.00078 +EDGE_SE3:QUAT 567 568 4.09411 -0.0592813 0.0238923 0.000889118 -0.0116109 0.00663969 0.99991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00216 -1.98897e-05 -0.0929961 3.99946 -0.00030636 4.00198 +EDGE_SE3:QUAT 568 569 4.3571 -0.0778374 -0.0251696 0.000782316 0.00373341 -0.00340118 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 1.05618e-05 0.0299001 3.99994 -5.06109e-05 4.00018 +EDGE_SE3:QUAT 569 570 4.11484 -0.173445 0.0247482 0.0024256 0.0011117 -0.0268017 0.999637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.11259e-05 0.00966375 3.99999 -0.000132864 3.99715 +EDGE_SE3:QUAT 570 571 3.96526 -0.29729 0.0259462 -0.00163876 0.0162152 -0.0707487 0.997361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00405 -0.000539604 0.127474 3.99902 -0.00450369 3.98404 +EDGE_SE3:QUAT 571 572 4.23871 -0.570584 0.011833 -0.0040603 -0.000561207 -0.134131 0.990955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.18265e-05 -0.0108259 3.99999 0.000869247 3.92806 +EDGE_SE3:QUAT 572 573 4.25978 -0.754399 -0.00533625 0.00228468 -0.00304893 -0.164127 0.986432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -4.49709e-05 -0.0189937 3.99998 0.00140861 3.89234 +EDGE_SE3:QUAT 573 574 3.95015 -0.651323 -0.00712581 0.0010333 0.00359404 -0.150851 0.988549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -3.41007e-05 0.02962 3.99995 -0.002256 3.9092 +EDGE_SE3:QUAT 528 573 0.455068 6.02046 0.0329638 -0.000346175 0.0110437 -0.918162 0.396051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000148472 0.00381868 3.99998 0.0287634 0.627711 +EDGE_SE3:QUAT 529 573 -3.59058 6.19472 0.0281423 -0.00152259 0.012069 -0.925802 0.377813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000229549 -0.00203992 3.99976 0.0358817 0.571378 +EDGE_SE3:QUAT 574 575 4.00761 -0.691184 0.00840245 0.00404132 0.00864825 -0.148204 0.988911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 -0.000146114 0.074023 3.99967 -0.00560212 3.91351 +EDGE_SE3:QUAT 526 574 5.72632 3.38083 0.000222331 -0.00271785 0.0136504 -0.964555 0.263514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000237828 -0.00994286 3.99932 0.0506831 0.27848 +EDGE_SE3:QUAT 527 574 1.49439 3.46603 0.0305383 0.00343725 0.0118009 -0.965334 0.26073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000137169 0.016751 4.00032 0.0326984 0.272299 +EDGE_SE3:QUAT 528 574 -2.75009 3.58084 0.00844107 0.00160968 0.0112171 -0.967466 0.252749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000172499 0.00847545 3.99997 0.0348204 0.255882 +EDGE_SE3:QUAT 575 576 4.22218 -0.597765 -0.0105053 -0.000640362 0.00296277 -0.102106 0.994769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -2.71196e-05 0.0225539 3.99997 -0.00113196 3.95842 +EDGE_SE3:QUAT 525 575 6.40754 1.86819 0.0233497 0.0014945 0.00802162 -0.99274 0.120001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.85958e-05 0.00621734 3.99987 0.0295233 0.0578328 +EDGE_SE3:QUAT 526 575 1.94807 1.93148 0.0178818 0.00478602 0.0114743 -0.992973 0.11769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000224976 0.0196893 4.00018 0.0398781 0.0559066 +EDGE_SE3:QUAT 527 575 -2.35316 2.03215 -0.000750175 0.0110855 0.0104062 -0.993248 0.115009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 0.000128574 0.0453357 4.00212 0.0302122 0.0536621 +EDGE_SE3:QUAT 528 575 -6.53261 2.20788 -0.00593967 0.00954392 0.00959522 -0.994241 0.106305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000148036 0.0389077 4.00153 0.0292919 0.0458041 +EDGE_SE3:QUAT 576 577 4.39883 -0.267245 0.00701003 0.00147525 0.00164226 -0.0277736 0.999612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 8.25849e-06 0.0136144 3.99999 -0.000191171 3.99696 +EDGE_SE3:QUAT 524 576 6.30383 1.32948 0.0304537 0.00320529 0.00904827 -0.999784 0.0184247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.00012289 0.0128296 3.99986 0.0356909 0.00171762 +EDGE_SE3:QUAT 525 576 2.21005 1.42865 0.00407727 0.0035741 0.00858047 -0.999799 0.0177914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000127069 0.014305 3.99994 0.0337876 0.00160279 +EDGE_SE3:QUAT 526 576 -2.26352 1.51111 -0.0321957 0.00650897 0.012633 -0.999776 0.0157081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000331796 0.0260513 4.0001 0.0496918 0.0017741 +EDGE_SE3:QUAT 527 576 -6.54945 1.64231 -0.105767 0.0130558 0.0124498 -0.999758 0.0126263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99929 0.000613914 0.0522422 4.00221 0.0485038 0.00190797 +EDGE_SE3:QUAT 577 578 4.04204 -0.0915076 0.0209248 0.00028622 -0.00125995 0.0016514 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.38062e-06 -0.0100853 3.99999 -8.31819e-06 4.00001 +EDGE_SE3:QUAT 523 577 6.09436 1.3236 0.0359999 -0.00551032 -0.00821652 0.999895 0.0106307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.00018283 0.022047 4.00019 0.0333296 0.0008513 +EDGE_SE3:QUAT 524 577 1.88418 1.4358 0.0180495 -0.00442356 -0.00746563 0.999922 0.00901817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000132161 0.0176977 4.00008 0.0301778 0.0006313 +EDGE_SE3:QUAT 525 577 -2.2357 1.54282 -0.0150385 -0.00505462 -0.00728097 0.999917 0.00936928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.00014881 0.0202225 4.00018 0.0294995 0.000670936 +EDGE_SE3:QUAT 526 577 -6.61929 1.64357 -0.0775532 -0.008126 -0.0109473 0.99983 0.0123966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000362943 0.0325165 4.00052 0.0445908 0.00137612 +EDGE_SE3:QUAT 578 579 4.02284 -0.101983 0.0185979 0.00372493 -0.0025386 0.00309612 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -3.76859e-05 -0.020447 3.99997 -3.11441e-05 4.00007 +EDGE_SE3:QUAT 522 578 6.30692 1.37125 0.0565986 -0.00812246 -0.00947308 0.999851 0.0119385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000317627 0.0325004 4.00065 0.0386663 0.00120794 +EDGE_SE3:QUAT 523 578 2.06953 1.4963 0.0147953 -0.00418324 -0.00779802 0.999922 0.00885863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000129746 0.0167363 4.00002 0.0314843 0.000631759 +EDGE_SE3:QUAT 524 578 -2.15424 1.59311 0.00298205 -0.00316645 -0.00744901 0.999942 0.00713777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.28225e-05 0.0126678 3.99993 0.0299738 0.000468529 +EDGE_SE3:QUAT 525 578 -6.25408 1.70756 -0.0358956 -0.00389487 -0.00691258 0.999939 0.00767934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000107465 0.0155819 4.00004 0.0278871 0.000491018 +EDGE_SE3:QUAT 579 580 4.43311 -0.0715045 -0.00197791 -0.00178519 0.00215639 0.00376293 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.50717e-05 0.0173316 3.99998 3.24599e-05 4.00002 +EDGE_SE3:QUAT 521 579 6.38968 1.4165 0.0182788 -0.000509762 -0.00489476 0.999887 0.0141785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.32139e-06 0.00203961 3.99991 0.0196268 0.000901486 +EDGE_SE3:QUAT 522 579 2.31495 1.55571 0.0111355 -0.00536453 -0.00537101 0.999935 0.00854217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000119084 0.0214611 4.00033 0.0218498 0.000526376 +EDGE_SE3:QUAT 523 579 -1.944 1.6527 0.00567854 -0.0016956 -0.00403573 0.999976 0.00538448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.70294e-05 0.00678286 3.99998 0.0162149 0.000193205 +EDGE_SE3:QUAT 524 579 -6.16927 1.75023 -0.00171213 -0.000424884 -0.00329902 0.999987 0.00388994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.28352e-06 0.0016996 3.99996 0.0132087 0.000104867 +EDGE_SE3:QUAT 580 581 4.00828 -0.0969299 0.0176437 0.000460324 -0.00149666 0.00238766 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.63131e-06 -0.0119865 3.99999 -1.42906e-05 4.00001 +EDGE_SE3:QUAT 520 580 6.11033 1.46111 0.0242477 -0.0048955 -0.00369149 0.999814 0.0182667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 8.04347e-05 0.0195919 4.00031 0.0154707 0.00149053 +EDGE_SE3:QUAT 521 580 2.00195 1.60035 0.0124644 -0.00260288 -0.00638269 0.999924 0.0102546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.46685e-05 0.0104137 3.99994 0.0257379 0.000613373 +EDGE_SE3:QUAT 522 580 -2.12469 1.69741 -0.031582 -0.00776553 -0.00716261 0.999934 0.00452039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000227263 0.0310646 4.00075 0.0289386 0.000532308 +EDGE_SE3:QUAT 523 580 -6.36948 1.77469 -0.0113898 -0.00386947 -0.00569277 0.999975 0.00141429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.82635e-05 0.0154786 4.00011 0.0228163 0.000198037 +EDGE_SE3:QUAT 581 582 4.35548 -0.0654455 0.00682249 -0.000478845 0.000469119 0.00704616 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.73539e-07 0.00379316 4 1.34083e-05 3.99981 +EDGE_SE3:QUAT 519 581 6.27762 1.53454 0.0209699 -0.00231987 -0.0037978 0.999693 0.0243751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.52479e-05 0.00928749 4.00002 0.0156211 0.0024592 +EDGE_SE3:QUAT 520 581 2.11582 1.69713 0.0085319 -0.00330793 -0.00304751 0.999864 0.0158704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.31546e-05 0.0132368 4.00013 0.0126029 0.00109101 +EDGE_SE3:QUAT 521 581 -1.98551 1.7723 0.0144845 -0.00117094 -0.00606006 0.999953 0.00752928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.63928e-05 0.00468439 3.99987 0.024307 0.000379967 +EDGE_SE3:QUAT 522 581 -6.13535 1.82947 -0.0745295 -0.0063251 -0.00658486 0.999955 0.00238958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000168128 0.0253018 4.00046 0.0264652 0.000357961 +EDGE_SE3:QUAT 582 583 4.36312 -0.0834364 0.024186 -0.000988688 -0.000725561 -3.9728e-05 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.86924e-06 -0.00580496 4 1.0282e-07 4.00001 +EDGE_SE3:QUAT 466 582 2.04939 6.60517 0.102994 0.00676031 0.00367042 -0.461663 0.887022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -0.000239768 0.0526338 3.99991 -0.0141139 3.14816 +EDGE_SE3:QUAT 518 582 5.99023 1.63324 0.0355654 -0.00501839 -0.00549145 0.999598 0.0273648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.00011888 0.0200961 4.00025 0.0230251 0.00322898 +EDGE_SE3:QUAT 519 582 1.95791 1.79822 0.0147314 -0.00282204 -0.0041656 0.999842 0.0170587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.77001e-05 0.0112932 4.00005 0.0170359 0.00126846 +EDGE_SE3:QUAT 520 582 -2.19701 1.8951 -0.0124236 -0.00370976 -0.00373639 0.999951 0.00837725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.72223e-05 0.0148408 4.00016 0.0151926 0.000393484 +EDGE_SE3:QUAT 521 582 -6.34091 1.89771 0.0148251 -0.00155131 -0.00657287 0.999977 0.000491139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.06426e-05 0.00620564 3.99987 0.0262973 0.000183485 +EDGE_SE3:QUAT 583 584 4.06971 -0.223757 0.023208 -0.00426253 0.00701106 -0.0567681 0.998354 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -0.000171916 0.0529263 3.99983 -0.00147753 3.98781 +EDGE_SE3:QUAT 466 583 4.49599 3.01504 0.074509 0.0056154 0.00339519 -0.461487 0.887123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 -0.000194062 0.0456518 3.99994 -0.0120859 3.14864 +EDGE_SE3:QUAT 467 583 -1.38355 3.64371 0.057793 0.00308666 0.00564497 -0.251551 0.967823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 -0.000153031 0.0498731 3.99987 -0.00647402 3.74751 +EDGE_SE3:QUAT 468 583 -6.91165 1.45711 -0.11287 0.00258133 -0.00955883 0.00443518 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00144 -8.92989e-05 -0.0766296 3.99963 -0.000164517 4.00139 +EDGE_SE3:QUAT 517 583 6.23777 1.75271 -0.00922631 -0.00026528 -0.00902798 0.99923 0.0381712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.53054e-05 0.00105933 3.99967 0.0360599 0.00615403 +EDGE_SE3:QUAT 518 583 1.63567 1.93521 0.0170605 -0.00436713 -0.00634035 0.999597 0.02733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000113183 0.0174881 4.00011 0.0262701 0.00323688 +EDGE_SE3:QUAT 519 583 -2.39328 2.01438 0.0184783 -0.00218388 -0.00513897 0.999836 0.0172094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.3017e-05 0.00873954 3.99996 0.0208415 0.00131237 +EDGE_SE3:QUAT 520 583 -6.57906 2.0289 -0.0163015 -0.00312523 -0.00428838 0.999949 0.00864277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.43043e-05 0.0125026 4.00008 0.0173671 0.000413279 +EDGE_SE3:QUAT 584 585 4.0328 -0.635732 0.00363297 0.00356592 0.0075519 -0.150035 0.988645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.001 -0.000113384 0.0647251 3.99975 -0.00496185 3.91101 +EDGE_SE3:QUAT 466 584 6.62281 -0.411469 0.0563987 0.00510006 0.0118472 -0.51101 0.859478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00168 -0.00147366 0.0860567 4.00027 -0.0207578 2.95726 +EDGE_SE3:QUAT 467 584 2.01549 1.50019 0.0359595 0.000644065 0.013718 -0.305907 0.951962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00233 -0.00116409 0.096968 3.99973 -0.0141358 3.62801 +EDGE_SE3:QUAT 468 584 -2.91283 1.27782 -0.00800085 -0.0014512 -0.00243864 -0.0521644 0.998634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 7.00214e-06 -0.0203367 3.99997 0.000537443 3.98922 +EDGE_SE3:QUAT 469 584 -7.09624 -1.56069 -0.0868965 0.00402327 -0.00796102 0.221847 0.975041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00114 0.00025275 -0.0694223 3.99974 -0.00791459 3.80434 +EDGE_SE3:QUAT 516 584 6.65004 2.14677 9.50861e-05 -0.000526728 -0.00815877 0.994889 0.100645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.60738e-05 0.00207191 3.99974 0.0322303 0.0407809 +EDGE_SE3:QUAT 517 584 2.22773 2.27716 0.0263327 -0.00689749 -0.0129108 0.995392 0.0947675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.0002906 0.0278784 3.99972 0.055673 0.0369004 +EDGE_SE3:QUAT 518 584 -2.37903 2.3871 0.018684 -0.011122 -0.0107146 0.996324 0.084258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000595389 0.0449185 4.00103 0.0495674 0.0295228 +EDGE_SE3:QUAT 519 584 -6.43912 2.37977 0.0314095 -0.00889982 -0.00953192 0.997166 0.074089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000396807 0.0358663 4.0006 0.0428647 0.0227413 +EDGE_SE3:QUAT 585 586 3.92006 -0.720282 0.0149276 -0.00352912 -0.00120289 -0.172804 0.984949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.83685e-05 -0.0163678 3.99998 0.00161194 3.88062 +EDGE_SE3:QUAT 467 585 4.89874 -1.36252 -0.0617377 0.00429931 0.019723 -0.445373 0.895118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00423 -0.00325385 0.133301 4.00028 -0.0274211 3.21087 +EDGE_SE3:QUAT 468 585 1.02633 0.22826 0.0124841 0.00231563 0.00428288 -0.201532 0.97947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -6.0163e-05 0.0376483 3.99992 -0.003909 3.83789 +EDGE_SE3:QUAT 469 585 -3.18498 -0.381561 -0.0142844 0.00679945 0.00078603 0.0730178 0.997307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -5.72478e-06 0.000301169 4 -6.21217e-05 3.97867 +EDGE_SE3:QUAT 470 585 -6.5405 -3.0844 0.0109985 0.003066 0.00320995 0.342509 0.939504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.84275e-05 0.00967952 4.00001 0.000662692 3.53076 +EDGE_SE3:QUAT 516 585 2.83332 3.56585 0.015294 -0.00664686 -0.00368829 0.9685 0.248896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.00022168 0.0284888 4.00029 0.0249372 0.248169 +EDGE_SE3:QUAT 517 585 -1.52741 3.65803 0.00373227 -0.012362 -0.00937476 0.969788 0.243457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000721188 0.0525821 4.00062 0.0547293 0.238582 +EDGE_SE3:QUAT 518 585 -6.13578 3.68271 -0.0468217 -0.0170282 -0.00769503 0.972197 0.233417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.00147451 0.0727008 4.00245 0.0567965 0.220137 +EDGE_SE3:QUAT 586 587 4.01841 -0.778078 0.00924891 0.00140645 -0.00251108 -0.176491 0.984298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -3.00977e-05 -0.0162407 3.99999 0.00131756 3.87547 +EDGE_SE3:QUAT 468 586 4.35532 -1.97577 -0.0141108 -0.00218625 0.00414008 -0.367978 0.929823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -7.77315e-05 0.0178437 4.00001 -0.00224203 3.45844 +EDGE_SE3:QUAT 469 586 0.796551 -0.510632 -0.0122357 0.00302083 0.00030141 -0.100359 0.994947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.84207e-06 0.00598849 4 -0.000360704 3.95972 +EDGE_SE3:QUAT 470 586 -3.09779 -1.09426 0.00093763 -0.000597483 0.00139878 0.17458 0.984642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 5.55047e-06 0.0119089 3.99999 0.0010607 3.87812 +EDGE_SE3:QUAT 471 586 -6.49024 -2.74832 -0.0355402 -0.00790575 -0.00188114 0.356779 0.934154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000104543 0.0187059 3.99994 0.00551941 3.4909 +EDGE_SE3:QUAT 515 586 3.97635 6.1051 0.0406043 -0.00607651 -0.0118324 0.918692 0.39475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000216173 0.0234675 3.99938 0.0461258 0.624092 +EDGE_SE3:QUAT 516 586 -0.25351 6.08924 -0.00337544 -0.00531637 -0.00856831 0.910867 0.412576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000102964 0.0211516 3.99965 0.035149 0.681366 +EDGE_SE3:QUAT 587 588 4.04254 -0.71802 -0.00317067 0.00614027 0.0127134 -0.140845 0.989931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00282 -0.000272462 0.109006 3.99928 -0.00783548 3.92362 +EDGE_SE3:QUAT 469 587 4.57298 -2.07339 -0.0137055 0.00402247 -0.00173303 -0.274509 0.961575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 9.9567e-06 0.000258002 4 -0.000715663 3.69857 +EDGE_SE3:QUAT 470 587 0.93138 -0.440861 -0.00434802 0.00102152 -0.000968154 -0.00183722 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.98176e-06 -0.00772268 4 7.11016e-06 4 +EDGE_SE3:QUAT 471 587 -2.99019 -0.642039 -0.0209026 -0.00511699 -0.00488903 0.186333 0.982461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 0.00011355 -0.0259153 3.99998 -0.00199637 3.86128 +EDGE_SE3:QUAT 472 587 -7.2077 -1.27575 -0.110614 -0.00540134 -0.0158393 0.262204 0.964867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00222 0.00133401 -0.0976879 3.99974 -0.0115144 3.72734 +EDGE_SE3:QUAT 588 589 4.47473 -0.552846 -0.0191611 0.00154998 0.00525719 -0.0922211 0.995723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -3.0314e-05 0.0432321 3.99989 -0.00201104 3.96645 +EDGE_SE3:QUAT 470 588 4.96647 -1.17596 0.00170553 0.00688173 0.0118151 -0.142925 0.989639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00248 -0.000190334 0.103339 3.99935 -0.00758134 3.92096 +EDGE_SE3:QUAT 471 588 1.01463 0.159732 0.0186841 -0.000560325 0.0081403 0.0460204 0.998907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 5.51686e-05 0.0652398 3.99974 0.00150212 3.99259 +EDGE_SE3:QUAT 472 588 -3.37784 0.149066 0.0166452 -0.000629687 -0.00244349 0.123379 0.992356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.15029e-05 -0.0181807 3.99998 -0.00109326 3.93919 +EDGE_SE3:QUAT 589 590 4.118 -0.185549 -0.0106018 -0.00298861 -0.00596689 -0.0175737 0.999823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 5.72575e-05 -0.0483487 3.99985 0.000424168 3.99935 +EDGE_SE3:QUAT 471 589 5.50692 0.0206798 -0.07065 -5.91952e-05 0.0132973 -0.0464108 0.998834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00281 -0.000199388 0.106067 3.99931 -0.00246323 3.99419 +EDGE_SE3:QUAT 472 589 1.07743 0.700944 0.0226174 0.000487639 0.00278693 0.0313352 0.999505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 1.11228e-05 0.0220799 3.99997 0.000344927 3.99619 +EDGE_SE3:QUAT 473 589 -3.18549 0.776511 0.0361355 0.00178641 0.00327323 0.048083 0.998836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.36263e-05 0.0250666 3.99996 0.000594143 3.99091 +EDGE_SE3:QUAT 590 591 3.9688 -0.0833602 0.00539644 -0.00293841 0.00734879 0.00079097 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 -8.54674e-05 0.0588286 3.99978 1.94703e-05 4.00086 +EDGE_SE3:QUAT 472 590 5.18984 0.773184 -0.0126969 -0.00213726 -0.00320757 0.013495 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.01838e-05 -0.0253082 3.99996 -0.000170507 3.99943 +EDGE_SE3:QUAT 473 590 0.907822 0.98888 0.000423761 -0.000975178 -0.00279735 0.030523 0.99953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 1.62418e-05 -0.0219911 3.99997 -0.000333847 3.99639 +EDGE_SE3:QUAT 474 590 -3.53015 1.07811 -0.0487188 0.00229143 -0.00739876 0.034198 0.999385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00088 -2.31846e-05 -0.0600374 3.99977 -0.00102887 3.99622 +EDGE_SE3:QUAT 591 592 4.35761 -0.0799741 0.0437199 0.000293229 -0.00690716 0.0027552 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 -4.9524e-06 -0.0552756 3.99981 -7.58542e-05 4.00073 +EDGE_SE3:QUAT 473 591 4.82947 1.13739 0.0230722 -0.00409823 0.00424018 0.0312028 0.999496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -5.91778e-05 0.0354071 3.99992 0.000558337 3.99642 +EDGE_SE3:QUAT 474 591 0.394274 1.25478 0.0143941 -0.000894232 -0.000383995 0.0350301 0.999386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.24742e-06 -0.00269071 4 -4.49029e-05 3.99509 +EDGE_SE3:QUAT 475 591 -4.08229 1.4049 0.00500931 -0.0033056 0.00519731 0.0310998 0.999497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -5.02634e-05 0.0427547 3.99988 0.000668865 3.99659 +EDGE_SE3:QUAT 592 593 4.44727 -0.0758608 0.0375456 0.00413219 -0.00304657 0.00418389 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -4.99864e-05 -0.0245796 3.99996 -5.06352e-05 4.00008 +EDGE_SE3:QUAT 474 592 4.75365 1.48169 0.0626795 -0.000436423 -0.00712605 0.0377584 0.999261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0008 5.80164e-05 -0.0566989 3.9998 -0.00106951 3.9951 +EDGE_SE3:QUAT 475 592 0.220687 1.57887 -0.000272412 -0.00280821 -0.00171142 0.033756 0.999425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.91235e-05 -0.0125312 3.99999 -0.000205147 3.99548 +EDGE_SE3:QUAT 476 592 -4.23617 1.73335 0.0149295 -0.00293985 0.00418198 0.0223116 0.999738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -4.098e-05 0.0342195 3.99993 0.000383372 3.9983 +EDGE_SE3:QUAT 593 594 4.22409 -0.0853097 0.00461888 0.00103452 -0.00619481 0.00441458 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -2.16118e-05 -0.0496184 3.99985 -0.000108651 4.00054 +EDGE_SE3:QUAT 475 593 4.68654 1.7969 0.052334 0.00117074 -0.00441282 0.037873 0.999272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -2.95465e-06 -0.0357607 3.99992 -0.000679642 3.99458 +EDGE_SE3:QUAT 476 593 0.191988 1.84631 0.0150515 0.00115629 0.00116651 0.0266078 0.999645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.91846e-06 0.00895321 4 0.000117468 3.99719 +EDGE_SE3:QUAT 477 593 -4.24985 2.00075 0.0618845 -0.00145643 0.00602802 0.0136718 0.999887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 -2.33413e-05 0.0484556 3.99985 0.000330598 3.99984 +EDGE_SE3:QUAT 594 595 4.26686 -0.0714708 -0.0206742 0.00320239 0.00388154 0.00422381 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 5.08967e-05 0.0308903 3.99994 6.6281e-05 4.00017 +EDGE_SE3:QUAT 476 594 4.41253 1.9964 0.00598983 0.00249825 -0.00468625 0.0306276 0.999517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -3.15483e-05 -0.0383576 3.99991 -0.000590592 3.99662 +EDGE_SE3:QUAT 477 594 -0.0011217 2.0417 0.00826665 -0.000285624 2.41271e-05 0.0180094 0.999838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.89073e-08 0.000254636 4 2.4779e-06 3.9987 +EDGE_SE3:QUAT 478 594 -4.29146 2.19044 -0.0145101 -0.00195546 -0.00495384 0.0053992 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 4.17581e-05 -0.0395055 3.9999 -0.000107707 4.00027 +EDGE_SE3:QUAT 595 596 4.1812 -0.0731561 -0.00293202 -0.000309577 0.0132744 0.00438322 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00282 2.07524e-06 0.106274 3.99929 0.000232041 4.00274 +EDGE_SE3:QUAT 477 595 4.29901 2.12506 -0.00826658 0.00268109 0.00409215 0.022314 0.999739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 5.12253e-05 0.0319965 3.99994 0.000355324 3.99826 +EDGE_SE3:QUAT 478 595 0.0278399 2.1648 0.00633676 0.00100968 -0.00112208 0.00959597 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.31349e-06 -0.00909171 3.99999 -4.37753e-05 3.99965 +EDGE_SE3:QUAT 479 595 -4.39278 2.32438 -0.105468 0.00248238 -0.0136424 -0.00299515 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00295 -0.000149036 -0.109118 3.99926 0.000174769 4.00294 +EDGE_SE3:QUAT 596 597 4.17784 -0.086301 0.0441703 0.00063084 -0.000870657 0.000282052 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.19277e-06 -0.00696741 4 -9.71212e-07 4.00001 +EDGE_SE3:QUAT 478 596 4.18296 2.1613 0.00995116 0.000786617 0.0123404 0.0139029 0.999827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00243 8.95543e-05 0.0986154 3.99939 0.000689115 4.00166 +EDGE_SE3:QUAT 479 596 -0.211151 2.21667 0.00568543 0.0020993 -0.000229507 0.00144231 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.97616e-06 -0.00187238 4 -1.35627e-06 3.99999 +EDGE_SE3:QUAT 480 596 -4.30891 2.31247 -0.0289223 0.00297158 0.000364437 -0.00420923 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.61442e-06 0.00306547 4 -6.54662e-06 3.99993 +EDGE_SE3:QUAT 597 598 4.06142 -0.0982779 0.0209819 -0.00172209 -0.00503914 -0.00262158 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 3.31841e-05 -0.0403703 3.9999 5.19028e-05 4.00038 +EDGE_SE3:QUAT 479 597 3.97889 2.14633 0.0532027 0.00278431 -0.00133048 0.00141915 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.48453e-05 -0.0106912 3.99999 -7.4784e-06 4.00002 +EDGE_SE3:QUAT 480 597 -0.154177 2.18823 0.0066915 0.00373847 -0.000686659 -0.00349482 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -9.9148e-06 -0.00533629 4 9.27371e-06 3.99996 +EDGE_SE3:QUAT 481 597 -4.18362 2.2515 0.0345943 0.00549405 0.0050009 0.000924388 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 0.000110262 0.0399478 3.9999 2.17488e-05 4.0004 +EDGE_SE3:QUAT 598 599 4.4674 -0.107471 -0.00673095 -0.000602656 -0.000777025 -0.000124002 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.87169e-06 -0.00621711 4 3.76753e-07 4.00001 +EDGE_SE3:QUAT 480 598 3.9403 2.04876 0.030711 0.00181878 -0.00567098 -0.00672197 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -4.62562e-05 -0.0452229 3.99987 0.000153273 4.00033 +EDGE_SE3:QUAT 481 598 -0.118568 2.15104 0.0124478 0.00345323 9.49459e-05 -0.00128263 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.4335e-06 0.000812702 4 -5.31726e-07 3.99999 +EDGE_SE3:QUAT 482 598 -4.4546 2.20213 0.0614897 0.00514875 0.00340759 0.00703172 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 7.05995e-05 0.0268242 3.99996 9.5208e-05 3.99998 +EDGE_SE3:QUAT 599 600 4.26968 -0.0919263 0.010277 -0.00149112 -0.000942539 7.60605e-05 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.62205e-06 -0.00753895 4 -3.18477e-07 4.00001 +EDGE_SE3:QUAT 481 599 4.33839 2.03119 0.00480704 0.00276463 -0.00069953 -0.00147805 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.66241e-06 -0.00554713 4 4.11941e-06 4 +EDGE_SE3:QUAT 482 599 0.00224992 2.16725 0.0277185 0.00444266 0.00250419 0.00683083 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.44195e-05 0.0196678 3.99998 6.7411e-05 3.99991 +EDGE_SE3:QUAT 483 599 -4.29999 2.2403 -0.0254005 0.00283442 -0.00207205 0.00998818 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.30685e-05 -0.0169137 3.99998 -8.47321e-05 3.99967 +EDGE_SE3:QUAT 600 601 4.05778 -0.100313 0.036979 0.000192624 0.00028574 -0.0114434 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.00678e-07 0.00231192 4 -1.32773e-05 3.99948 +EDGE_SE3:QUAT 482 600 4.27385 2.13389 0.0105609 0.0030973 0.00155471 0.0065251 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.91265e-05 0.0121943 3.99999 3.96948e-05 3.99987 +EDGE_SE3:QUAT 483 600 -0.0402978 2.24538 0.00107732 0.00125266 -0.00317512 0.00972663 0.999947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -1.36565e-05 -0.0255444 3.99996 -0.000124169 3.99978 +EDGE_SE3:QUAT 484 600 -4.26046 2.34199 -0.0485925 -0.00267664 -0.00144557 0.00821429 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.54018e-05 -0.0112995 3.99999 -4.61761e-05 3.99976 +EDGE_SE3:QUAT 601 602 4.31443 -0.268614 0.0367841 0.000821627 0.00543252 -0.0553547 0.998452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 -2.17094e-05 0.0438098 3.99988 -0.00121552 3.98822 +EDGE_SE3:QUAT 483 601 4.02979 2.2287 0.0663335 0.00132128 -0.0024834 -0.00179178 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -1.33656e-05 -0.019839 3.99998 1.79613e-05 4.00009 +EDGE_SE3:QUAT 484 601 -0.209679 2.31962 5.0922e-05 -0.00281609 -0.000699844 -0.00323947 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.04934e-06 -0.00570808 4 9.27053e-06 3.99997 +EDGE_SE3:QUAT 485 601 -4.3305 2.44408 -0.0626651 -0.00256988 -0.00452264 -0.0098009 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 4.21389e-05 -0.0364805 3.99992 0.000178016 3.99995 +EDGE_SE3:QUAT 602 603 4.2158 -0.504039 -0.0144463 -0.00622603 0.00413622 -0.124939 0.992136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -9.14818e-05 0.0230793 3.99998 -0.00123271 3.93769 +EDGE_SE3:QUAT 484 602 4.09614 2.01841 0.0437214 -0.00146628 0.00445746 -0.0583796 0.998283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -5.14077e-05 0.0344547 3.99993 -0.000994819 3.98666 +EDGE_SE3:QUAT 485 602 -0.0273791 2.09857 0.0101009 -0.00076429 0.000642037 -0.0649627 0.997887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.17073e-06 0.00450969 4 -0.000139683 3.98312 +EDGE_SE3:QUAT 486 602 -4.1072 2.32822 0.0214625 0.000460708 -0.000954406 -0.0907011 0.995878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.33392e-06 -0.00704255 4 0.000310382 3.96711 +EDGE_SE3:QUAT 603 604 4.20897 -0.738451 0.00432975 0.000628054 0.000398303 -0.163987 0.986462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.43388e-07 0.00427252 4 -0.000380498 3.89244 +EDGE_SE3:QUAT 485 603 4.083 1.05244 -0.00692619 -0.0069694 0.00537798 -0.188908 0.981955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000128218 0.0253157 3.99999 -0.00182217 3.85741 +EDGE_SE3:QUAT 486 603 -0.0477849 1.09035 0.00742732 -0.00488943 0.00356837 -0.21415 0.976782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -4.82753e-05 0.0144242 4 -0.00102461 3.8166 +EDGE_SE3:QUAT 487 603 -3.86336 1.71618 0.00667553 -0.00833224 0.00618896 -0.313498 0.949532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 -5.12032e-05 0.0130978 4.00002 -1.48462e-05 3.60688 +EDGE_SE3:QUAT 604 605 4.23225 -0.793303 0.0116135 0.00377793 0.00340196 -0.169864 0.985454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 5.69931e-07 0.0336007 3.99993 -0.00303659 3.88487 +EDGE_SE3:QUAT 486 604 3.46232 -1.35575 0.00130471 -0.00449179 0.00317179 -0.371506 0.928414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.47573e-06 0.00212394 4 0.0011924 3.44792 +EDGE_SE3:QUAT 487 604 -0.921115 -1.40681 -0.00051594 -0.00837882 0.00489727 -0.464891 0.885314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000143467 -0.0128196 3.99993 0.0076569 3.13548 +EDGE_SE3:QUAT 488 604 -5.51325 0.174376 -0.0333857 -0.00881871 0.00472366 -0.641911 0.766714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000161982 -0.0322348 3.99978 0.0201566 2.352 +EDGE_SE3:QUAT 605 606 4.31906 -0.780896 -0.0303151 0.00200556 0.0106068 -0.147881 0.988946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00182 -0.000323218 0.085628 3.99958 -0.00635154 3.91436 +EDGE_SE3:QUAT 487 605 0.839911 -5.30015 0.0225717 -0.00385473 0.00466281 -0.608424 0.793589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 4.11183e-05 -0.00255419 3.99999 0.00611378 2.51924 +EDGE_SE3:QUAT 488 605 -5.52003 -4.1022 0.0115828 -0.0038608 0.00322999 -0.762523 0.646941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.85973e-05 -0.0146365 3.99993 0.0132233 1.67427 +EDGE_SE3:QUAT 606 607 4.02124 -0.455622 0.0142935 0.00187229 -0.000108077 -0.0744759 0.997221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.27793e-06 0.000809664 4 -5.10094e-05 3.97781 +EDGE_SE3:QUAT 607 608 4.2083 -0.178025 0.0195469 0.000402699 -0.00078731 -0.017506 0.999846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.49959e-06 -0.00621102 4 5.41161e-05 3.99878 +EDGE_SE3:QUAT 608 609 4.36226 -0.167228 0.016649 0.00296324 -0.000568278 -0.0129109 0.999912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.9115e-06 -0.00408599 4 2.54059e-05 3.99934 +EDGE_SE3:QUAT 609 610 4.42681 -0.115304 0.0295242 -0.00150073 0.0013565 -0.00466879 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -8.26239e-06 0.0107676 3.99999 -2.51361e-05 3.99994 +EDGE_SE3:QUAT 610 611 4.41924 -0.11789 0.0218059 0.000606222 -0.00283661 -0.00206635 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -7.27173e-06 -0.0226783 3.99997 2.35443e-05 4.00011 +EDGE_SE3:QUAT 611 612 4.47718 -0.11121 0.0126294 -0.000219825 -0.000531762 0.00023529 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.69086e-07 -0.00425348 4 -5.01868e-07 4 +EDGE_SE3:QUAT 612 613 4.28249 -0.0921107 0.0136412 0.00167576 -9.44727e-05 0.000879309 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.52809e-07 -0.000773459 4 -3.42274e-07 4 +EDGE_SE3:QUAT 613 614 4.18165 -0.0967959 0.0389456 0.000444321 0.00703736 0.00213734 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 1.50527e-05 0.0562968 3.9998 6.07178e-05 4.00077 +EDGE_SE3:QUAT 614 615 4.32469 -0.0829343 0.0020154 -5.23856e-05 0.0019441 0.0021144 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.15615e-07 0.0155542 3.99998 1.64403e-05 4.00004 +EDGE_SE3:QUAT 615 616 4.24838 -0.0890743 0.0174021 -0.000254609 -0.000793327 0.0019858 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.36875e-07 -0.00634053 4 -6.29738e-06 3.99999 +EDGE_SE3:QUAT 616 617 4.23124 -0.139165 0.0190909 0.000631998 -0.000791693 -0.0143378 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.16465e-06 -0.00622288 4 4.43564e-05 3.99919 +EDGE_SE3:QUAT 554 616 5.9215 -3.74186 0.0368441 -0.00710717 -0.00415279 0.969784 0.243826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000251553 0.0303704 4.00032 0.0272378 0.238237 +EDGE_SE3:QUAT 555 616 -0.417817 -4.97514 0.0640863 -0.00355644 0.00334091 0.88242 0.470437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000168105 0.0208925 4.00027 0.00385071 0.885378 +EDGE_SE3:QUAT 556 616 -6.48024 -3.39525 0.121774 -0.0010767 0.00693575 0.763297 0.646009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000219454 0.02099 4.00026 -0.000257393 1.6695 +EDGE_SE3:QUAT 617 618 4.13769 -0.278307 0.0245702 -0.00253985 0.000432161 -0.0590268 0.998253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.41095e-06 0.00164436 4 -3.06576e-05 3.98606 +EDGE_SE3:QUAT 553 617 6.75106 0.579629 -0.00603562 -0.00169434 0.000295981 0.999952 0.00963164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.34631e-06 0.0067783 4.00005 -0.00105312 0.000382839 +EDGE_SE3:QUAT 554 617 2.25836 -1.61878 0.0144869 -0.00620085 -0.00368641 0.966181 0.257765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000190301 0.0266469 4.00022 0.0242941 0.26611 +EDGE_SE3:QUAT 555 617 -2.66123 -1.38912 0.0473633 -0.00272261 0.00370778 0.875511 0.483176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000123995 0.0173327 4.00021 0.00114563 0.933931 +EDGE_SE3:QUAT 556 617 -7.06143 0.786505 0.096306 -0.000137219 0.00703657 0.753948 0.656896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000153835 0.0167272 4.0002 -0.00249563 1.72621 +EDGE_SE3:QUAT 618 619 4.1296 -0.547324 0.0111796 -0.00148208 0.00184432 -0.125355 0.992109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.61203e-05 0.0122021 3.99999 -0.000710987 3.93718 +EDGE_SE3:QUAT 552 618 6.03498 3.09447 0.0306806 0.00393638 0.00608181 -0.980447 0.196652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 1.90531e-05 0.0170017 4.00033 0.016056 0.154833 +EDGE_SE3:QUAT 553 618 2.61371 0.925624 0.0065943 -0.00232803 -0.00216657 0.99763 0.0687267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.4995e-05 0.0093723 4.00005 0.00983828 0.0189398 +EDGE_SE3:QUAT 554 618 -1.19234 0.684755 -0.00472663 -0.00715625 -0.00650565 0.949224 0.314453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000178132 0.0309323 3.99996 0.0360411 0.396125 +EDGE_SE3:QUAT 555 618 -4.64975 2.26394 0.0391407 -0.00441645 0.00157165 0.845357 0.534182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 0.000195065 0.0253748 4.0002 0.011208 1.14162 +EDGE_SE3:QUAT 619 620 4.13177 -0.710638 0.00525933 -0.00249935 -0.00180739 -0.155815 0.987781 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 6.4902e-06 -0.0185336 3.99998 0.00155108 3.90297 +EDGE_SE3:QUAT 551 619 5.21316 3.31761 0.0332071 0.00313302 0.00848669 -0.961709 0.273922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 3.86857e-05 0.0152562 4.0003 0.021401 0.30033 +EDGE_SE3:QUAT 552 619 2.00469 1.99441 0.00482568 0.0047457 0.00831968 -0.997334 0.0723472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000145215 0.0191575 4.00023 0.0301156 0.0212568 +EDGE_SE3:QUAT 553 619 -1.41505 2.01769 0.00106999 -0.00393837 -0.0037627 0.98114 0.193221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.39856e-05 0.0163942 4.00005 0.0195258 0.149505 +EDGE_SE3:QUAT 554 619 -4.19198 3.58448 -0.0194264 -0.00841204 -0.00794805 0.902319 0.430913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 6.66551e-05 0.0365562 3.99969 0.041646 0.743611 +EDGE_SE3:QUAT 620 621 4.08371 -0.72451 -0.00517718 -0.00310643 0.000876825 -0.163835 0.986483 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.92048e-06 0.000736004 4 0.000114278 3.89263 +EDGE_SE3:QUAT 550 620 5.12378 2.58471 0.0213967 0.00172366 0.00649828 -0.959901 0.28026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 3.80871e-05 0.0088023 4.0001 0.0174716 0.314292 +EDGE_SE3:QUAT 551 620 1.32826 1.72811 0.00210993 -0.000614411 0.0109099 -0.992598 0.120955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.59434e-05 -0.00235575 3.99955 0.0426351 0.0589832 +EDGE_SE3:QUAT 552 620 -2.18087 2.10315 -0.0223872 -0.00153959 -0.0112295 0.996411 0.0838905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.58363e-05 0.00617021 3.99949 0.0451528 0.0286734 +EDGE_SE3:QUAT 553 620 -4.95423 4.24006 -0.0140594 -0.00218623 -0.0071368 0.9391 0.343564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.97573e-05 0.00783557 3.99981 0.0257792 0.472352 +EDGE_SE3:QUAT 621 622 4.35863 -0.819424 -0.00551466 0.00576373 0.0191501 -0.154134 0.987848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00614 -0.000983876 0.158483 3.99855 -0.0123409 3.91124 +EDGE_SE3:QUAT 549 621 5.23373 1.45699 -0.0262046 -0.00675616 0.00984405 -0.977021 0.212806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -0.000163989 -0.0280428 3.99976 0.0459712 0.181897 +EDGE_SE3:QUAT 550 621 1.29552 0.995337 -0.00426645 0.000640802 0.00988745 -0.9928 0.119373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000105908 0.00275301 3.99969 0.0375437 0.0573593 +EDGE_SE3:QUAT 551 621 -2.80522 1.45266 0.0126578 0.00190801 -0.0135031 0.998985 0.0429275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000158355 -0.00766433 3.99939 0.0531069 0.00809231 +EDGE_SE3:QUAT 552 621 -6.09296 3.49814 -0.00991526 -0.000458373 -0.0140155 0.969234 0.245739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000280449 0.000324934 3.99951 0.0486247 0.24219 +EDGE_SE3:QUAT 622 623 4.02088 -0.522132 0.0194437 0.00752586 -0.00435031 -0.0892932 0.995967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00011534 -0.0263638 3.99997 0.0010532 3.96828 +EDGE_SE3:QUAT 548 622 4.99274 0.505501 0.0824021 0.0115589 0.0110249 -0.994092 0.107358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99929 0.000179762 0.0471334 4.00227 0.033047 0.0469435 +EDGE_SE3:QUAT 549 622 0.953797 0.384461 0.0220168 0.0115349 0.00713288 -0.998102 0.0600664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9994 0.000144223 0.0463981 4.00214 0.0227681 0.0151023 +EDGE_SE3:QUAT 550 622 -3.1298 0.754039 -0.00755686 -0.0188228 -0.00628544 0.999186 0.035133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99866 0.000753581 0.0754251 4.0053 0.0304074 0.0065926 +EDGE_SE3:QUAT 623 624 4.26862 -0.243819 -0.0148495 0.00268468 -0.001835 -0.0231952 0.999726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.0075e-05 -0.0139212 3.99999 0.000158722 3.9979 +EDGE_SE3:QUAT 547 623 5.37679 0.017416 0.0294351 0.00197595 0.0104443 -0.999761 0.0191017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.69092e-05 0.0079101 3.99965 0.0414361 0.00190458 +EDGE_SE3:QUAT 548 623 0.96084 0.152591 0.00233251 0.00710896 0.00422394 -0.999798 0.0183441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 9.99226e-05 0.0284502 4.00076 0.0158429 0.00161121 +EDGE_SE3:QUAT 549 623 -3.10634 0.41091 -0.052581 -0.00722148 -0.000253853 0.999541 0.029418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 4.39917e-05 0.0289227 4.00083 0.00271218 0.00367282 +EDGE_SE3:QUAT 550 623 -7.1108 1.54765 -0.137375 -0.0135833 -0.000665731 0.992177 0.124098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99937 0.000561593 0.0555628 4.00276 0.0158573 0.0624469 +EDGE_SE3:QUAT 624 625 4.54438 -0.130639 0.0122846 -0.000638438 -0.00435524 -0.00335286 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 9.60765e-06 -0.0348693 3.99992 5.81907e-05 4.00026 +EDGE_SE3:QUAT 546 624 5.18686 -0.0218727 0.0138146 -0.00325919 -0.00709351 0.999909 0.0109831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.06817e-05 0.01304 3.99996 0.0286527 0.000730295 +EDGE_SE3:QUAT 547 624 1.10082 0.109037 -0.00669467 0.000114169 -0.00797159 0.99996 0.00402235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.6824e-06 -0.000456751 3.99975 0.0318804 0.000318879 +EDGE_SE3:QUAT 548 624 -3.31581 0.254393 -0.0722149 -0.00523968 -0.00178884 0.999973 0.00482674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 4.0549e-05 0.0209593 4.00042 0.00735836 0.000216553 +EDGE_SE3:QUAT 549 624 -7.33562 0.909908 -0.132626 -0.00502113 0.00183357 0.99861 0.0524445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -5.03956e-06 0.0201691 4.00041 -0.00518371 0.0111104 +EDGE_SE3:QUAT 625 626 4.49873 -0.0949267 0.0182869 -0.00185891 0.00575676 0.000736512 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 -4.22589e-05 0.0460756 3.99987 1.54959e-05 4.00053 +EDGE_SE3:QUAT 545 625 4.85839 0.0747247 -0.0105476 0.0010013 -0.00731816 0.999768 0.0202578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.72919e-05 -0.00400853 3.99981 0.0290798 0.00185704 +EDGE_SE3:QUAT 546 625 0.645008 0.195194 0.00262984 0.00109555 -0.00772591 0.999865 0.0144597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.02217e-05 -0.00438418 3.99979 0.0307601 0.00107774 +EDGE_SE3:QUAT 547 625 -3.43296 0.266909 0.0143364 0.00417175 -0.00854008 0.999928 0.00736696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000143621 -0.01669 4 0.033912 0.000574244 +EDGE_SE3:QUAT 626 627 4.00369 -0.0854806 0.0391875 -0.00248177 -0.00318707 0.00133878 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.19019e-05 -0.0254573 3.99996 -1.76373e-05 4.00015 +EDGE_SE3:QUAT 544 626 4.65405 0.233615 0.0442477 -0.0104325 -0.00585508 0.999628 0.0245293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000299638 0.0417679 4.00153 0.0254456 0.00300504 +EDGE_SE3:QUAT 545 626 0.454104 0.343224 0.0155655 -0.00478619 -0.00881115 0.999761 0.019443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000166314 0.0191572 4.00002 0.0359582 0.00192726 +EDGE_SE3:QUAT 546 626 -3.85351 0.415369 0.0356973 -0.00481902 -0.00916244 0.999854 0.0136169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000174563 0.0192836 4.00001 0.0371605 0.00117993 +EDGE_SE3:QUAT 627 628 4.02619 -0.0958481 0.0180248 0.000388455 -0.00155657 0.00256668 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.27231e-06 -0.0124645 3.99999 -1.59791e-05 4.00001 +EDGE_SE3:QUAT 543 627 4.96349 0.385494 0.0358859 -0.00832001 -0.0076002 0.999536 0.0283023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000283815 0.0333212 4.00079 0.0322329 0.00374173 +EDGE_SE3:QUAT 544 627 0.716691 0.510158 0.0017368 -0.00726804 -0.00847518 0.999667 0.0232517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000260513 0.0290978 4.00049 0.0352144 0.00268446 +EDGE_SE3:QUAT 545 627 -3.49181 0.583029 0.0221729 -0.00196862 -0.0113454 0.99977 0.0181191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.19051e-05 0.00787917 3.99953 0.0456276 0.00184942 +EDGE_SE3:QUAT 628 629 4.38468 -0.0902423 -0.0371517 0.00444685 0.00879951 0.00301129 0.999947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00115 0.000161782 0.0702512 3.99969 0.000114014 4.0012 +EDGE_SE3:QUAT 542 628 5.0854 0.581893 -0.0245941 0.00879513 -0.0105421 0.999448 0.0302524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -0.000336531 -0.0352343 4.00093 0.0399615 0.004371 +EDGE_SE3:QUAT 543 628 0.966754 0.70359 -0.00606285 -0.00680536 -0.00730822 0.999622 0.0256128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000214474 0.0272493 4.00047 0.030585 0.00304376 +EDGE_SE3:QUAT 544 628 -3.20737 0.779785 -0.0371391 -0.00567557 -0.00806524 0.999741 0.0205338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000187112 0.0227182 4.00021 0.0331633 0.00209067 +EDGE_SE3:QUAT 629 630 4.0382 -0.088923 0.0290557 -9.86895e-05 0.00501196 0.00289169 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -2.35657e-07 0.0401022 3.9999 5.79386e-05 4.00037 +EDGE_SE3:QUAT 541 629 4.98927 0.825467 -0.00115148 0.00128957 -0.00598867 0.99949 0.0313544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.81118e-05 -0.00516766 3.9999 0.0235726 0.00407813 +EDGE_SE3:QUAT 542 629 0.792635 0.931036 0.0195728 0.000181946 -0.00576976 0.999608 0.0273844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.13951e-05 -0.000729628 3.99987 0.0229956 0.00313206 +EDGE_SE3:QUAT 543 629 -3.42116 1.01845 -0.0983905 -0.0156947 -0.00256074 0.999618 0.0226209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99903 0.000292562 0.0628206 4.00387 0.0130872 0.00307694 +EDGE_SE3:QUAT 630 631 4.39528 -0.0944185 0.04704 0.00356768 0.00199011 0.00369572 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.83698e-05 0.0157622 3.99998 2.93636e-05 4.00001 +EDGE_SE3:QUAT 540 630 5.20043 1.04482 0.0472291 -0.00781493 -0.00740866 0.999484 0.030267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000259413 0.0313034 4.00067 0.0314664 0.00415723 +EDGE_SE3:QUAT 541 630 1.03857 1.15026 0.0382894 -0.00348735 -0.00575394 0.999569 0.0285674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.00099e-05 0.0139661 4.00004 0.0237662 0.00345449 +EDGE_SE3:QUAT 542 630 -3.25056 1.24016 0.0498354 -0.00474212 -0.00582378 0.999672 0.0244809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000116007 0.0189857 4.00019 0.0241908 0.00263379 +EDGE_SE3:QUAT 631 632 4.31972 -0.0903314 0.0402601 -0.00101974 -0.00974882 0.00339694 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00152 4.7534e-05 -0.0779734 3.99962 -0.000134868 4.00147 +EDGE_SE3:QUAT 539 631 5.13552 1.30598 0.0665163 -0.0114622 -0.00585362 0.999536 0.0275958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000344963 0.045901 4.00187 0.0259165 0.00374121 +EDGE_SE3:QUAT 540 631 0.869338 1.40689 0.0281246 -0.0097092 -0.00374433 0.999586 0.0268082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000201526 0.0388777 4.0014 0.0170399 0.00332548 +EDGE_SE3:QUAT 541 631 -3.38999 1.50105 0.0587492 -0.00546501 -0.00216732 0.999676 0.0247509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 6.37283e-05 0.0218798 4.00044 0.00973905 0.00259391 +EDGE_SE3:QUAT 632 633 4.17319 -0.0809423 0.0283871 -0.00154572 -0.00805966 0.00364652 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 5.5483e-05 -0.0644228 3.99974 -0.000119904 4.00098 +EDGE_SE3:QUAT 538 632 5.0732 1.55488 0.0560864 -0.00996938 -0.00728355 0.999645 0.0236237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000334515 0.0399123 4.00129 0.0309922 0.00287094 +EDGE_SE3:QUAT 539 632 0.811157 1.62337 0.0169107 -0.00189548 -0.00698762 0.999688 0.0239213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.5232e-05 0.00758815 3.99985 0.0282728 0.00250327 +EDGE_SE3:QUAT 540 632 -3.48973 1.72708 -0.00818825 -0.000117645 -0.00503545 0.999719 0.023144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.32644e-06 0.000470455 3.9999 0.0201364 0.00224405 +EDGE_SE3:QUAT 633 634 4.04592 -0.0802105 0.00741249 -0.00238217 0.00648677 0.00518067 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -5.68223e-05 0.0520474 3.99983 0.000132589 4.00057 +EDGE_SE3:QUAT 537 633 5.03326 1.76286 -0.0268343 0.0062056 -0.0070369 0.999822 0.0163687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000165362 -0.0248337 4.00045 0.0273217 0.0014126 +EDGE_SE3:QUAT 538 633 0.918016 1.82137 0.0102115 -0.00177206 -0.00904866 0.99976 0.0198747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.22269e-05 0.00709263 3.99971 0.0364395 0.00192471 +EDGE_SE3:QUAT 539 633 -3.38693 1.90816 0.0335914 0.00624873 -0.00905143 0.999731 0.0204361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000219061 -0.0250134 4.00035 0.0351534 0.00213605 +EDGE_SE3:QUAT 634 635 4.32292 -0.0653376 0.0371627 -0.00590628 0.00121483 -0.00275187 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -2.80252e-05 0.00952306 3.99999 -1.32163e-05 3.99999 +EDGE_SE3:QUAT 536 634 5.0958 1.9511 0.0244368 0.00234247 0.00881421 -0.999958 0.000681995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.29151e-05 0.00937095 3.99978 0.0352437 0.000334358 +EDGE_SE3:QUAT 537 634 1.02769 1.96774 0.0301159 -0.000323071 -0.00921104 0.999895 0.0111436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.34639e-06 0.00129252 3.99966 0.03686 0.000836871 +EDGE_SE3:QUAT 538 634 -3.14257 2.05869 0.00126551 -0.00852722 -0.011125 0.999794 0.0146703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000389503 0.0341253 4.0006 0.0454912 0.0016694 +EDGE_SE3:QUAT 635 636 4.00018 -0.269449 0.0376099 -0.00044916 0.00689708 -0.0683512 0.997637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 -8.87541e-05 0.0544319 3.99982 -0.00185305 3.98205 +EDGE_SE3:QUAT 535 635 5.13722 2.358 0.0225097 0.00513727 0.00752062 -0.998326 0.057118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000136061 0.0206615 4.0003 0.0275016 0.0133467 +EDGE_SE3:QUAT 536 635 0.760765 2.00991 0.0430973 -0.00346981 -0.0149531 0.99988 0.00210464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000204307 0.0138839 3.99929 0.0598672 0.000962069 +EDGE_SE3:QUAT 537 635 -3.26069 2.12156 0.0669946 -0.00149572 -0.0152736 0.99979 0.0136146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.64142e-05 0.00598595 3.99909 0.0612224 0.00168782 +EDGE_SE3:QUAT 636 637 4.10448 -0.692766 -0.00435794 0.000815999 0.00422201 -0.15977 0.987145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -5.6129e-05 0.0340311 3.99993 -0.0027253 3.89818 +EDGE_SE3:QUAT 534 636 4.81307 2.97932 0.00450772 0.000578122 0.00594343 -0.99181 0.127583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.2661e-05 0.00246725 3.9999 0.0222312 0.0652372 +EDGE_SE3:QUAT 535 636 1.11794 2.17409 0.0192161 -0.0114269 -0.00855394 0.999832 0.0115065 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000420122 0.0457195 4.00174 0.0352798 0.00136329 +EDGE_SE3:QUAT 536 636 -3.22949 2.29267 0.0637247 -0.0093726 -0.0154514 0.997361 0.0703139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000549403 0.0377391 3.99998 0.0663038 0.0212376 +EDGE_SE3:QUAT 637 638 4.2798 -0.860569 0.00307643 0.00116139 -0.000537213 -0.185147 0.98271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.8231e-07 -0.00155727 4 5.75926e-05 3.86288 +EDGE_SE3:QUAT 533 637 3.99655 3.29542 0.0212838 0.00405921 0.00769089 -0.989463 0.144524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 9.10982e-05 0.0169235 4.00026 0.0245767 0.0837776 +EDGE_SE3:QUAT 534 637 0.67451 2.58351 -0.00653387 -0.00386627 -0.00564894 0.999452 0.0323887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.9274e-05 0.0154886 4.00008 0.0235386 0.00439478 +EDGE_SE3:QUAT 535 637 -2.96771 2.94394 -0.0681151 -0.014073 -0.00910063 0.985126 0.171012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000951585 0.0583627 4.00164 0.0524977 0.118554 +EDGE_SE3:QUAT 638 639 4.25351 -0.89047 0.00811151 0.0020778 0.0013773 -0.18599 0.982548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.83324e-06 0.0149822 3.99999 -0.00151864 3.86169 +EDGE_SE3:QUAT 531 638 6.14546 4.22838 0.019143 0.00328623 0.00735088 -0.968302 0.249651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 2.73116e-05 0.0152298 4.00028 0.0187712 0.249464 +EDGE_SE3:QUAT 532 638 2.8954 3.11679 0.0279342 0.00336389 0.0121154 -0.993033 0.117163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000225852 0.0138882 3.99987 0.0436998 0.0554427 +EDGE_SE3:QUAT 533 638 -0.357044 2.90144 -0.0124753 -0.00244339 -0.00713735 0.999108 0.0415377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.69675e-05 0.00979542 3.99986 0.0292368 0.0071396 +EDGE_SE3:QUAT 534 638 -3.53169 3.72235 -0.026297 -0.00229183 -0.00506648 0.976237 0.216635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.91904e-06 0.00937776 3.9999 0.0217129 0.187869 +EDGE_SE3:QUAT 639 640 4.02203 -0.65996 -0.00217164 0.000859868 0.00229872 -0.130761 0.991411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -9.57088e-06 0.0192544 3.99998 -0.00127781 3.9317 +EDGE_SE3:QUAT 530 639 5.6207 3.42652 0.00615323 -0.00136787 0.0109738 -0.988436 0.151233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.57698e-05 -0.00535163 3.99953 0.04302 0.0919666 +EDGE_SE3:QUAT 531 639 1.98209 2.92428 -0.0033417 0.00382659 0.00596361 -0.997861 0.0649878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 8.06355e-05 0.0154165 4.00016 0.0216237 0.0170708 +EDGE_SE3:QUAT 532 639 -1.46113 2.98794 0.0134738 -0.00271308 -0.0105013 0.99751 0.0696896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.71915e-05 0.0109039 3.9996 0.0429995 0.0199209 +EDGE_SE3:QUAT 533 639 -4.52374 4.12613 -0.00883517 -0.00231059 -0.00532582 0.973973 0.226591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.59217e-06 0.00943083 3.99988 0.0225915 0.205531 +EDGE_SE3:QUAT 640 641 4.37702 -0.501907 0.000345466 0.00463191 3.35483e-05 -0.0722704 0.997374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.26812e-05 0.00426923 4 -0.000202609 3.97911 +EDGE_SE3:QUAT 529 640 5.59699 2.89462 0.0454815 0.00352801 0.00975148 -0.998856 0.046675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.00015411 0.0141678 3.9999 0.0374809 0.00911653 +EDGE_SE3:QUAT 530 640 1.60767 2.84982 0.016032 -0.000498943 0.0101434 -0.999722 0.0212608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.75689e-06 -0.00199648 3.99959 0.0406105 0.00222161 +EDGE_SE3:QUAT 531 640 -2.06598 3.06992 -0.0371737 -0.00519625 -0.00590904 0.997827 0.0654126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000138609 0.0209061 4.0002 0.026094 0.0173958 +EDGE_SE3:QUAT 532 640 -5.32999 4.18764 0.00282276 -0.00359698 -0.00994588 0.979872 0.199344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.68665e-05 0.0145901 3.99959 0.0413926 0.159452 +EDGE_SE3:QUAT 641 642 4.02624 -0.127425 0.0128017 -0.0014069 -0.0017267 0.00233061 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 9.84657e-06 -0.0137743 3.99999 -1.61366e-05 4.00003 +EDGE_SE3:QUAT 528 641 5.3438 2.98491 0.0481128 -0.00478626 -0.00523756 0.999956 0.0060661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000102244 0.0191467 4.00025 0.0211829 0.000351015 +EDGE_SE3:QUAT 529 641 1.2054 2.96995 0.0210981 -0.00293299 -0.00534361 0.999655 0.0255329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.149e-05 0.0117432 4 0.0219389 0.00276262 +EDGE_SE3:QUAT 530 641 -2.79303 3.15583 0.0286473 0.00121356 -0.00545722 0.998677 0.0511113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.56222e-05 -0.0048793 3.99992 0.0211915 0.010568 +EDGE_SE3:QUAT 572 641 4.98205 4.94051 0.137395 0.012282 0.00366893 -0.546109 0.837616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 -0.000618852 0.0817705 3.99981 -0.0277835 2.80873 +EDGE_SE3:QUAT 573 641 -1.16785 5.62625 0.123534 0.00811561 0.00688706 -0.401264 0.915901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00123 -0.000519294 0.0772496 3.99978 -0.0170718 3.35744 +EDGE_SE3:QUAT 642 643 4.05786 -0.0650427 0.0154754 0.00104819 0.00084051 0.0115327 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.61076e-06 0.00657769 4 3.76652e-05 3.99948 +EDGE_SE3:QUAT 527 642 5.57631 3.10461 0.0510132 0.00449078 0.00766001 -0.999949 0.0048607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000137498 0.0179651 4.0001 0.0304662 0.000407233 +EDGE_SE3:QUAT 528 642 1.35003 3.14573 0.0205284 -0.00300917 -0.00646668 0.999968 0.00358189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.74045e-05 0.0120376 3.99997 0.0259528 0.000255934 +EDGE_SE3:QUAT 529 642 -2.78705 3.28836 0.010506 -0.00129105 -0.00679132 0.999707 0.023186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.71599e-05 0.00516799 3.99983 0.0273677 0.00234439 +EDGE_SE3:QUAT 572 642 6.49399 1.23273 0.0674423 0.0102094 0.00298864 -0.544136 0.838929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -0.00041433 0.0676423 3.99986 -0.0229427 2.8168 +EDGE_SE3:QUAT 573 642 1.46181 2.6108 0.0526076 0.00594155 0.00567946 -0.399087 0.916876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 -0.000339838 0.0604708 3.99988 -0.0131215 3.36383 +EDGE_SE3:QUAT 574 642 -3.37719 2.37718 0.0317669 0.00552494 0.00283534 -0.256131 0.966622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 2.22258e-06 0.0367282 3.99991 -0.00532521 3.73792 +EDGE_SE3:QUAT 643 644 4.06815 -0.0315193 0.0218833 -0.00230893 0.00778962 0.0100985 0.999916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00096 -5.76093e-05 0.0626002 3.99975 0.000313355 4.00057 +EDGE_SE3:QUAT 526 643 5.74234 3.03356 0.00513865 -0.0010023 0.00677383 -0.999793 0.0191588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.04365e-05 -0.00401126 3.99983 0.0272235 0.00165761 +EDGE_SE3:QUAT 527 643 1.53596 3.11309 0.0369212 0.0055007 0.0066335 -0.999831 0.0162217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000139324 0.0220127 4.00034 0.0258068 0.00134027 +EDGE_SE3:QUAT 528 643 -2.69284 3.22528 0.0156286 0.00388433 0.00530957 -0.999948 0.0078518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.1356e-05 0.0155393 4.00014 0.0209925 0.000417146 +EDGE_SE3:QUAT 573 643 4.17338 -0.390384 0.00794984 0.00747819 0.0059289 -0.388349 0.921463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 -0.000363722 0.06848 3.99981 -0.0147467 3.39791 +EDGE_SE3:QUAT 574 643 0.134025 0.318022 0.0128935 0.00670559 0.00330239 -0.244876 0.969526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 1.64646e-05 0.0429985 3.99987 -0.00596311 3.7606 +EDGE_SE3:QUAT 575 643 -3.9685 -0.17435 -0.0594876 0.00430828 -0.00502767 -0.0987786 0.995087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -0.000118098 -0.0345614 3.99994 0.00161558 3.96127 +EDGE_SE3:QUAT 644 645 3.95227 -0.132657 0.00438471 0.00237819 0.000211689 -0.0074809 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.34227e-06 0.00190684 4 -7.39534e-06 3.99978 +EDGE_SE3:QUAT 525 644 6.2141 2.83848 0.0305878 0.00407572 0.00545284 -0.999489 0.0312331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 8.24963e-05 0.0163285 4.00018 0.0207426 0.00407642 +EDGE_SE3:QUAT 526 644 1.75983 2.90211 0.0356736 0.00705717 0.00916641 -0.999513 0.0289759 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000240264 0.0282681 4.00055 0.0349631 0.00386418 +EDGE_SE3:QUAT 527 644 -2.52018 3.00927 0.0117014 0.0134126 0.00880046 -0.999527 0.0262252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99923 0.000371172 0.0537058 4.00271 0.0323607 0.00373451 +EDGE_SE3:QUAT 528 644 -6.72936 3.19716 0.00989447 0.0119498 0.00762558 -0.999739 0.0178981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9994 0.00031032 0.0478221 4.00213 0.0287895 0.0020605 +EDGE_SE3:QUAT 574 644 3.66002 -1.61237 -0.00360231 0.00620741 0.0115411 -0.235771 0.97172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00243 -0.000577378 0.101708 3.99946 -0.0123599 3.78023 +EDGE_SE3:QUAT 575 644 -0.0244283 -1.00042 -0.00471697 0.00262701 0.00289095 -0.089057 0.996019 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 1.36951e-05 0.0256463 3.99996 -0.00117904 3.96844 +EDGE_SE3:QUAT 576 644 -4.01932 -1.27343 -0.0206279 0.00301517 0.000219552 0.0136348 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.66496e-06 0.00126263 4 7.48774e-06 3.99926 +EDGE_SE3:QUAT 645 646 4.04315 -0.126317 0.0164476 0.000580904 0.000746966 -0.00648898 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.66513e-06 0.00602059 4 -1.95745e-05 3.99984 +EDGE_SE3:QUAT 524 645 6.30494 2.62142 0.0370492 0.00372033 0.00348777 -0.999689 0.0244015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 4.56892e-05 0.0148951 4.00019 0.0132055 0.00248086 +EDGE_SE3:QUAT 525 645 2.21417 2.71837 0.00827093 0.00409484 0.00311274 -0.999705 0.0237363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.28295e-05 0.0163936 4.00024 0.0116573 0.00235488 +EDGE_SE3:QUAT 526 645 -2.14145 2.79995 -0.01386 0.00716977 0.00683723 -0.999723 0.0213325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000176452 0.0287 4.00069 0.0261018 0.0021967 +EDGE_SE3:QUAT 527 645 -6.37236 2.92554 -0.0864193 0.0138593 0.00668374 -0.99972 0.0179882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99921 0.000293078 0.0554616 4.00297 0.0247451 0.00221667 +EDGE_SE3:QUAT 575 645 3.83985 -1.8283 -0.0264093 0.00505581 0.00294791 -0.0964718 0.995319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 4.99564e-05 0.0290719 3.99994 -0.00148976 3.96298 +EDGE_SE3:QUAT 576 645 -0.0836643 -1.29216 -0.0195863 0.00531672 0.000436044 0.00558338 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 8.03122e-06 0.00313184 4 8.43191e-06 3.99988 +EDGE_SE3:QUAT 577 645 -4.38325 -1.26916 -0.0327593 0.00379402 -0.00104527 0.0333832 0.999435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.85319e-05 -0.00986678 3.99999 -0.000172943 3.99557 +EDGE_SE3:QUAT 646 647 4.15064 -0.123684 0.0212159 -7.66114e-05 -0.00183771 -0.00371046 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.62497e-07 -0.0147049 3.99999 2.72777e-05 4 +EDGE_SE3:QUAT 523 646 6.49071 2.43406 0.0428873 0.00545904 0.00330908 -0.999847 0.016298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 6.17536e-05 0.0218449 4.00045 0.0125179 0.00122102 +EDGE_SE3:QUAT 524 646 2.30668 2.53884 0.0214606 0.00441126 0.00296115 -0.999822 0.0180979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.48098e-05 0.0176538 4.00029 0.0111976 0.00141944 +EDGE_SE3:QUAT 525 646 -1.77676 2.65538 -0.00850255 0.00511059 0.00194073 -0.999831 0.0175647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 2.90151e-05 0.0204517 4.00041 0.00704002 0.00135107 +EDGE_SE3:QUAT 526 646 -6.09138 2.74535 -0.0567328 0.00814418 0.00562944 -0.999837 0.0151303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000162633 0.0325882 4.00097 0.0215269 0.00129712 +EDGE_SE3:QUAT 576 646 3.92307 -1.35745 -0.00772592 0.00629894 0.00133959 -0.000334787 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 3.38419e-05 0.0107414 3.99999 -1.5272e-06 4.00003 +EDGE_SE3:QUAT 577 646 -0.390084 -1.12076 -0.0123303 0.0045855 -0.000194613 0.0268287 0.99963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -8.00231e-06 -0.00303072 4 -4.7236e-05 3.99712 +EDGE_SE3:QUAT 578 646 -4.41263 -1.01758 -0.0198896 0.00441447 0.00118101 0.0251274 0.999674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.7577e-05 0.00810836 4 9.63762e-05 3.99749 +EDGE_SE3:QUAT 647 648 4.06861 -0.0995549 0.0176315 0.000564287 -0.00165574 -0.000429257 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.76452e-06 -0.0132431 3.99999 2.87934e-06 4.00004 +EDGE_SE3:QUAT 522 647 6.59254 2.28403 0.0701858 0.00753791 0.00489722 -0.999916 0.00928743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000136684 0.0301556 4.00083 0.0190304 0.000662917 +EDGE_SE3:QUAT 523 647 2.32949 2.40733 0.0249316 0.00352213 0.00333965 -0.999909 0.0125676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 4.43191e-05 0.014092 4.00016 0.0130001 0.000723687 +EDGE_SE3:QUAT 524 647 -1.83042 2.51356 0.00888386 0.00253048 0.00261964 -0.999887 0.0145773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.49879e-05 0.0101253 4.00008 0.0101783 0.000901536 +EDGE_SE3:QUAT 525 647 -5.92253 2.61875 -0.0302487 0.00326786 0.00212436 -0.999893 0.0140776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.45854e-05 0.0130754 4.00016 0.00812573 0.000851976 +EDGE_SE3:QUAT 577 647 3.77042 -1.01545 0.00641448 0.00475826 -0.00208092 0.0232253 0.999717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.1051e-05 -0.0179593 3.99998 -0.000213088 3.99792 +EDGE_SE3:QUAT 578 647 -0.264082 -0.924763 -0.0105477 0.00446555 -0.000700043 0.0212811 0.999763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -1.55513e-05 -0.00673642 4 -7.564e-05 3.9982 +EDGE_SE3:QUAT 579 647 -4.30954 -0.806448 -0.00461043 0.000559513 0.00177036 0.0182772 0.999831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 5.26943e-06 0.0140332 3.99999 0.000127894 3.99871 +EDGE_SE3:QUAT 648 649 4.1908 -0.0896048 0.00918237 -0.000393267 0.00314236 0.000233266 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -4.88884e-06 0.0251409 3.99996 2.83939e-06 4.00016 +EDGE_SE3:QUAT 521 648 6.63079 2.16079 0.0236292 0.000868569 0.00367301 -0.999988 0.00306453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.30342e-05 0.00347439 3.99996 0.0146704 9.43892e-05 +EDGE_SE3:QUAT 522 648 2.53544 2.30619 0.0210228 0.00598786 0.00408026 -0.999934 0.00888024 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 9.11925e-05 0.0239544 4.00052 0.0158955 0.000522064 +EDGE_SE3:QUAT 523 648 -1.73287 2.40964 0.00823241 0.00194257 0.00247756 -0.999923 0.0120308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.87087e-05 0.00777206 4.00004 0.00971989 0.000617688 +EDGE_SE3:QUAT 524 648 -5.94918 2.49874 -0.000561188 0.00110933 0.00213344 -0.999905 0.0135933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.53208e-06 0.00443862 4 0.00840925 0.000761717 +EDGE_SE3:QUAT 578 648 3.81414 -0.850763 0.0103279 0.00538092 -0.00222648 0.020699 0.999769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.99195e-05 -0.0191361 3.99998 -0.000201913 3.99838 +EDGE_SE3:QUAT 579 648 -0.233656 -0.758242 -0.00235396 0.0012658 0.00026655 0.0174177 0.999847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.14977e-06 0.00186691 4 1.54896e-05 3.99879 +EDGE_SE3:QUAT 580 648 -4.62685 -0.657734 -0.0201162 0.00289326 -0.00180989 0.0132987 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.07321e-05 -0.014937 3.99999 -0.000100101 3.99935 +EDGE_SE3:QUAT 649 650 4.197 -0.0948588 0.0237265 -0.00126969 -0.00257029 0.0014704 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.32688e-05 -0.0205403 3.99997 -1.52978e-05 4.0001 +EDGE_SE3:QUAT 520 649 6.56385 2.06351 0.0382638 -0.00607062 -0.000623388 0.99997 0.00487225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 1.94342e-05 0.0242829 4.00059 0.00273059 0.000244243 +EDGE_SE3:QUAT 521 649 2.43347 2.21507 0.0274711 0.00392203 0.00378668 -0.99998 0.00330112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 5.85667e-05 0.0156886 4.00019 0.0150439 0.0001617 +EDGE_SE3:QUAT 522 649 -1.6781 2.31641 -0.015281 0.00923928 0.00451323 -0.999906 0.00905184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000149698 0.036961 4.0013 0.0173882 0.000744887 +EDGE_SE3:QUAT 523 649 -5.93175 2.3965 0.00369636 0.00505031 0.00289854 -0.999908 0.0122702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 5.17479e-05 0.0202058 4.00038 0.0110956 0.0007351 +EDGE_SE3:QUAT 579 649 3.97051 -0.694796 0.0072998 0.000902416 0.00340758 0.0177011 0.999837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 1.70557e-05 0.0270572 3.99995 0.000239146 3.99893 +EDGE_SE3:QUAT 580 649 -0.412184 -0.618145 0.00422246 0.00258143 0.00124045 0.0133457 0.999907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.25539e-05 0.00950754 3.99999 6.26067e-05 3.99931 +EDGE_SE3:QUAT 581 649 -4.41646 -0.513794 0.00170425 0.00224278 0.00281563 0.0108338 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 2.68396e-05 0.02223 3.99997 0.000120311 3.99965 +EDGE_SE3:QUAT 650 651 4.19624 -0.0930649 0.0123442 0.000328629 0.00056719 0.00177684 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.57728e-07 0.00453049 4 4.02544e-06 3.99999 +EDGE_SE3:QUAT 519 650 6.53134 2.03021 0.0276051 -0.00271101 -0.00294776 0.999921 0.011888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.31665e-05 0.0108464 4.00008 0.0120451 0.000630986 +EDGE_SE3:QUAT 520 650 2.36834 2.18764 0.0120512 -0.00338438 -0.0020184 0.999987 0.00307944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.80703e-05 0.0135377 4.00017 0.00815729 0.000100385 +EDGE_SE3:QUAT 521 650 -1.77307 2.27838 0.0178737 0.00138701 0.00504405 -0.999975 0.00485335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.87372e-05 0.00554846 3.99993 0.0201211 0.000203136 +EDGE_SE3:QUAT 522 650 -5.92468 2.33641 -0.0663875 0.00656959 0.00575235 -0.999911 0.0100485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000143253 0.026283 4.00058 0.0224806 0.000702939 +EDGE_SE3:QUAT 580 650 3.77577 -0.594867 0.0164288 0.00170243 -0.00147089 0.0151435 0.999883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.54465e-06 -0.0120724 3.99999 -9.20904e-05 3.99912 +EDGE_SE3:QUAT 581 650 -0.231354 -0.505195 -0.00137281 0.00110541 0.000229038 0.0125665 0.99992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.03223e-07 0.00166519 4 1.0114e-05 3.99937 +EDGE_SE3:QUAT 582 650 -4.58017 -0.383297 -0.0137358 0.0015334 -0.000145642 0.00525186 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.8901e-07 -0.00126172 4 -3.39683e-06 3.99989 +EDGE_SE3:QUAT 651 652 4.14426 -0.0836811 0.0222435 -0.000537392 -0.0016352 0.00179302 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.62583e-06 -0.0130701 3.99999 -1.17487e-05 4.00003 +EDGE_SE3:QUAT 466 651 1.48093 6.69398 0.106423 0.00861781 0.00315429 -0.455139 0.890373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 -0.000205735 0.0583923 3.99984 -0.0160785 3.17224 +EDGE_SE3:QUAT 518 651 6.42005 2.02708 0.0449552 -0.00552148 -0.0033245 0.999778 0.0200808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.58906e-05 0.0220992 4.00043 0.0141735 0.00178534 +EDGE_SE3:QUAT 519 651 2.37189 2.20909 0.0196769 -0.00323783 -0.00241005 0.999943 0.00986324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.31919e-05 0.0129532 4.00014 0.00989383 0.000455558 +EDGE_SE3:QUAT 520 651 -1.78335 2.30166 -0.00258868 -0.00419601 -0.00151994 0.99999 0.000879927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.58721e-05 0.016784 4.00027 0.00610986 8.28553e-05 +EDGE_SE3:QUAT 521 651 -5.95231 2.31847 0.022676 0.00213059 0.00487979 -0.999964 0.00661671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.20983e-05 0.0085232 3.99998 0.0194045 0.000287423 +EDGE_SE3:QUAT 581 651 3.96124 -0.492573 0.00861314 0.00136853 0.000983266 0.0143647 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.48297e-06 0.00762782 4 5.42459e-05 3.99919 +EDGE_SE3:QUAT 582 651 -0.379645 -0.414942 0.000895184 0.00188718 0.000471871 0.00717756 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.39298e-06 0.00361212 4 1.27777e-05 3.9998 +EDGE_SE3:QUAT 583 651 -4.76984 -0.362692 -0.023555 0.00295529 0.000956321 0.00730938 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.09449e-05 0.00739067 4 2.67557e-05 3.9998 +EDGE_SE3:QUAT 652 653 3.98956 -0.0772227 0.0151977 -0.000412067 0.000345156 0.00247624 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.65139e-07 0.00277347 4 3.43775e-06 3.99998 +EDGE_SE3:QUAT 466 652 3.82106 3.3193 0.0708415 0.00741298 0.00168978 -0.453063 0.891446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -6.89873e-05 0.0443689 3.99988 -0.0126558 3.17942 +EDGE_SE3:QUAT 467 652 -2.12451 3.6258 0.0569807 0.0050694 0.0045442 -0.242639 0.970093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -6.00219e-05 0.0473773 3.99987 -0.00620586 3.76507 +EDGE_SE3:QUAT 517 652 6.86957 2.08457 -0.00845722 0.000300302 -0.00694252 0.999552 0.0291 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.93405e-05 -0.00120426 3.99981 0.0276408 0.00357878 +EDGE_SE3:QUAT 518 652 2.2983 2.27307 0.0223374 -0.003715 -0.00393368 0.999824 0.0179605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.18872e-05 0.0148673 4.00015 0.0162567 0.00141169 +EDGE_SE3:QUAT 519 652 -1.76611 2.37747 0.015011 -0.00151849 -0.00284007 0.999966 0.00764694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.71644e-05 0.00607454 4 0.0114516 0.000275915 +EDGE_SE3:QUAT 520 652 -5.91744 2.39724 -0.0159668 0.0026049 0.00226116 -0.999993 0.00110221 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.34275e-05 0.0104197 4.00009 0.00902195 5.23503e-05 +EDGE_SE3:QUAT 582 652 3.7149 -0.444471 0.0195774 0.00151229 -0.00129325 0.0094669 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -7.60523e-06 -0.0105164 3.99999 -4.99865e-05 3.99967 +EDGE_SE3:QUAT 583 652 -0.634841 -0.389579 -0.012356 0.00216961 -0.000584215 0.00941495 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.34016e-06 -0.00491818 4 -2.35167e-05 3.99965 +EDGE_SE3:QUAT 584 652 -4.56535 -0.68192 -0.1036 0.00628149 -0.00748838 0.0659056 0.997778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00088 -0.000107679 -0.0644824 3.99973 -0.00216697 3.98366 +EDGE_SE3:QUAT 653 654 4.06731 -0.0854054 -0.0236857 -0.000392742 0.00862043 0.00251523 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -9.07082e-06 0.0689926 3.9997 8.61378e-05 4.00116 +EDGE_SE3:QUAT 466 653 6.10925 0.0450598 0.0500038 0.00714075 0.0022654 -0.451029 0.892478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -0.000108583 0.0462964 3.99989 -0.012795 3.18682 +EDGE_SE3:QUAT 467 653 1.35444 1.68231 0.028831 0.00504301 0.00474871 -0.240269 0.970682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -6.75711e-05 0.0487343 3.99986 -0.00629625 3.76967 +EDGE_SE3:QUAT 468 653 -3.53561 1.12162 -0.0442527 0.0035847 -0.0102644 0.0158778 0.999815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00166 -0.000108284 -0.0827967 3.99957 -0.000650586 4.0007 +EDGE_SE3:QUAT 517 653 2.911 2.3822 0.0124605 -5.10593e-05 -0.00731495 0.999623 0.0264636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.81345e-06 0.000203301 3.99979 0.0292186 0.00301489 +EDGE_SE3:QUAT 518 653 -1.69677 2.49759 0.0110552 -0.00405541 -0.0043136 0.999861 0.015613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.35519e-05 0.0162278 4.00018 0.0177517 0.0011197 +EDGE_SE3:QUAT 519 653 -5.74361 2.51212 0.0241452 -0.00197708 -0.00336757 0.999979 0.00510965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.66374e-05 0.00790876 4.00002 0.0135504 0.000165976 +EDGE_SE3:QUAT 583 653 3.38932 -0.381471 0.0126049 0.00178943 -0.000284343 0.0116997 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.30761e-06 -0.00252547 4 -1.52585e-05 3.99945 +EDGE_SE3:QUAT 584 653 -0.626197 -0.240167 -0.0226674 0.00591869 -0.00717024 0.0682683 0.997624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00081 -9.24834e-05 -0.0618055 3.99975 -0.00215326 3.98231 +EDGE_SE3:QUAT 585 653 -4.57247 -1.00357 -0.100705 0.00281748 -0.0136628 0.217374 0.975989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00293 0.000837202 -0.108836 3.99941 -0.0118159 3.81395 +EDGE_SE3:QUAT 654 655 3.98962 -0.0910993 0.0190984 -0.000902514 0.00148604 -3.22425e-05 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.36636e-06 0.0118881 3.99999 -2.39485e-07 4.00004 +EDGE_SE3:QUAT 467 654 4.89498 -0.288774 -0.0441597 0.00652719 0.0132239 -0.237679 0.971232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00313 -0.000784324 0.114954 3.99932 -0.0140244 3.77734 +EDGE_SE3:QUAT 468 654 0.521486 1.15167 0.01049 0.0028517 -0.00170274 0.018369 0.999826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.92343e-05 -0.0142434 3.99999 -0.000132513 3.9987 +EDGE_SE3:QUAT 469 654 -4.11499 0.132432 -0.0129111 0.0079808 -0.00620264 0.290276 0.95689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00096 0.000180179 -0.0697384 3.99972 -0.0111322 3.66417 +EDGE_SE3:QUAT 516 654 3.26263 2.5836 0.00990855 -0.00188732 -0.00304495 0.999539 0.030141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.29998e-05 0.00755901 4.00001 0.012607 0.00368799 +EDGE_SE3:QUAT 517 654 -1.1359 2.67646 -0.00303695 -0.00866472 -0.00717865 0.999644 0.0242097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000280319 0.0346907 4.00092 0.030361 0.00287598 +EDGE_SE3:QUAT 518 654 -5.72463 2.7158 -0.0443161 -0.0127554 -0.00447686 0.999818 0.0134607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99936 0.000278681 0.0510333 4.00249 0.0192898 0.00146903 +EDGE_SE3:QUAT 583 654 7.41041 -0.378533 -0.00834876 0.00144855 0.00833376 0.0139975 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00109 7.12785e-05 0.0664229 3.99973 0.000467001 4.00032 +EDGE_SE3:QUAT 584 654 3.41914 0.226616 0.0105841 0.00489762 0.00126879 0.0708032 0.997477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 1.23012e-05 0.00592651 4 0.000159884 3.97996 +EDGE_SE3:QUAT 585 654 -0.829546 0.652387 -0.00803311 0.000891038 -0.00537563 0.219626 0.975569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 0.000132872 -0.0422083 3.99991 -0.00460366 3.8075 +EDGE_SE3:QUAT 586 654 -4.94199 -0.358387 -0.00615331 0.00526694 -0.00480753 0.385223 0.922796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 0.000229623 -0.0521717 3.9999 -0.0109801 3.40709 +EDGE_SE3:QUAT 655 656 4.4633 -0.146187 0.0358621 -1.26025e-05 -0.00242066 -0.0115055 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -1.49588e-06 -0.0193636 3.99998 0.000111395 3.99956 +EDGE_SE3:QUAT 468 655 4.50762 1.21365 0.045564 0.00176792 -5.57262e-05 0.0185726 0.999826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.54195e-07 -0.000839505 4 -9.01446e-06 3.99862 +EDGE_SE3:QUAT 469 655 -0.748943 2.27449 0.0676737 0.00618866 -0.0051237 0.290311 0.956899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 0.000128688 -0.0562757 3.99982 -0.00893807 3.66367 +EDGE_SE3:QUAT 470 655 -5.8718 0.462738 0.0674061 0.00443256 -0.0015531 0.540359 0.841422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 9.16235e-05 -0.0305508 3.99998 -0.0101089 2.83228 +EDGE_SE3:QUAT 515 655 3.64945 2.9085 0.0487944 -0.00516238 -0.00661692 0.999911 0.0104068 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000139448 0.020654 4.00023 0.0268935 0.000720681 +EDGE_SE3:QUAT 516 655 -0.725729 2.91748 0.0214178 -0.00318009 -0.00395471 0.999536 0.030019 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.31186e-05 0.012737 4.00008 0.0165469 0.00371367 +EDGE_SE3:QUAT 517 655 -5.10586 2.96967 -0.0504763 -0.0102829 -0.00791503 0.999627 0.0240396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000371902 0.0411694 4.00135 0.0336086 0.003018 +EDGE_SE3:QUAT 584 655 7.37308 0.710568 0.0226941 0.00407434 0.00272001 0.0710235 0.997463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.40468e-05 0.0181346 3.99998 0.000601512 3.9799 +EDGE_SE3:QUAT 585 655 2.80948 2.27639 0.052425 -0.000576498 -0.00417635 0.219721 0.975554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 8.60507e-05 -0.0295509 3.99996 -0.00309979 3.80711 +EDGE_SE3:QUAT 586 655 -2.06658 2.41873 0.0640451 0.00373308 -0.00378613 0.385113 0.922854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000139704 -0.0393566 3.99994 -0.00819043 3.40714 +EDGE_SE3:QUAT 587 655 -6.81161 0.886847 0.0847964 0.00407302 -0.000376812 0.541884 0.840443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 2.57281e-05 -0.0230907 3.99997 -0.00837839 2.82558 +EDGE_SE3:QUAT 656 657 4.31015 -0.201378 0.0245771 0.000840723 -0.000122994 -0.029645 0.99956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.51586e-07 -0.000683753 4 8.65101e-06 3.99648 +EDGE_SE3:QUAT 469 656 3.02799 4.62569 0.1632 0.00688731 -0.00714805 0.279363 0.960134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00112 0.000254406 -0.07253 3.99972 -0.0108676 3.68914 +EDGE_SE3:QUAT 470 656 -3.89063 4.45626 0.142371 0.00569612 -0.00355396 0.530592 0.847601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 0.00028098 -0.0467817 3.99999 -0.0141716 2.87444 +EDGE_SE3:QUAT 514 656 3.15086 3.30031 0.035619 0.00431226 0.00463731 -0.998073 0.0617308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 5.82316e-05 0.0173562 4.00027 0.016253 0.0153847 +EDGE_SE3:QUAT 515 656 -0.805745 3.1476 0.0416694 -0.00275644 -0.00686326 0.99974 0.021591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.09223e-05 0.0110336 3.99991 0.0278973 0.00208979 +EDGE_SE3:QUAT 516 656 -5.15095 3.33083 0.0284596 -0.000835108 -0.00437461 0.999143 0.0411414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.65331e-06 0.00334654 3.99993 0.0176987 0.00685171 +EDGE_SE3:QUAT 586 656 1.16084 5.49357 0.149203 0.00471536 -0.00599438 0.374445 0.927218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 0.00032136 -0.0574497 3.99989 -0.0113671 3.43999 +EDGE_SE3:QUAT 587 656 -4.83461 4.88702 0.141745 0.00531876 -0.00225868 0.531983 0.846736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 0.000155759 -0.0385213 3.99997 -0.0122828 2.86835 +EDGE_SE3:QUAT 657 658 4.18503 -0.352547 0.0378278 -0.00277131 0.00265869 -0.0870977 0.996192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -3.53252e-05 0.0181461 3.99998 -0.00074508 3.96974 +EDGE_SE3:QUAT 512 657 5.55479 4.28624 -0.0245208 0.000738232 0.000756888 -0.943935 0.33013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.91565e-06 0.0036128 4.00001 0.000497677 0.435948 +EDGE_SE3:QUAT 513 657 2.41938 3.07696 -0.00635251 0.00516056 0.00114857 -0.985674 0.168581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -8.73994e-05 0.0215471 4.00043 -0.00249156 0.1138 +EDGE_SE3:QUAT 514 657 -1.15418 2.96026 0.0197872 0.00423416 0.00423832 -0.999463 0.0322231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 6.13791e-05 0.0169643 4.00024 0.0158205 0.00428797 +EDGE_SE3:QUAT 515 657 -5.11203 3.53627 0.0441324 -0.00230973 -0.00599649 0.998647 0.0515951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.49555e-05 0.00926963 3.99991 0.0247773 0.0108236 +EDGE_SE3:QUAT 658 659 4.20672 -0.824537 0.0225928 0.000863905 0.00242902 -0.192294 0.981334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -2.08324e-05 0.0203091 3.99998 -0.001981 3.8522 +EDGE_SE3:QUAT 511 658 5.47939 3.02017 0.00895693 -0.000367486 0.00637655 -0.915948 0.401245 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 5.25132e-05 0.00151554 3.99998 0.01683 0.644088 +EDGE_SE3:QUAT 512 658 2.06829 1.93369 0.00127776 0.00227741 0.00441432 -0.969082 0.246687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 4.29945e-06 0.0104326 4.00013 0.0108085 0.243481 +EDGE_SE3:QUAT 513 658 -1.65471 2.00803 -0.0137904 0.00727722 0.00495137 -0.996607 0.0818298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 4.1719e-05 0.0294206 4.00088 0.0147469 0.0270573 +EDGE_SE3:QUAT 514 658 -5.36556 3.03809 0.0219031 -0.00636549 -0.00734008 0.998426 0.0552399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000207796 0.0255707 4.00031 0.0319462 0.0126255 +EDGE_SE3:QUAT 659 660 4.04661 -0.987512 0.0077396 -0.000956131 -0.000460244 -0.229675 0.973267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.86345e-07 -0.00593702 4 0.000770917 3.78901 +EDGE_SE3:QUAT 510 659 6.02026 1.32323 0.0415792 0.00455652 0.00662548 -0.942149 0.335099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.000144499 0.0230219 4.00058 0.00851913 0.449346 +EDGE_SE3:QUAT 511 659 2.00766 0.475304 0.0173893 0.00102539 0.00669943 -0.976102 0.217207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.44662e-05 0.00493091 3.99997 0.0219924 0.18885 +EDGE_SE3:QUAT 512 659 -2.01532 0.629804 0.00748794 0.00400587 0.00456815 -0.998445 0.0554154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 5.753e-05 0.0161035 4.00022 0.0163635 0.0124157 +EDGE_SE3:QUAT 513 659 -5.92825 2.11365 -0.0475688 -0.00873571 -0.00553115 0.99375 0.111153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000328994 0.0355268 4.00081 0.0291261 0.0499528 +EDGE_SE3:QUAT 660 661 4.23892 -0.910792 -0.00089671 0.00491966 0.00450939 -0.167568 0.985838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 8.07498e-07 0.0442777 3.99987 -0.00394025 3.88817 +EDGE_SE3:QUAT 509 660 6.40454 0.0650163 -0.0103126 0.000295209 0.0106093 -0.981631 0.190493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000149095 0.0018314 3.9997 0.0382024 0.145532 +EDGE_SE3:QUAT 510 660 2.26432 -0.474936 0.0087976 0.00219301 0.00790093 -0.993904 0.109943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.55953e-05 0.00901436 3.99994 0.028748 0.0485801 +EDGE_SE3:QUAT 511 660 -2.06368 -0.351199 0.0186865 0.00120239 -0.00720448 0.999893 0.0127099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.9391e-05 -0.00481124 3.99982 0.0286836 0.000857688 +EDGE_SE3:QUAT 512 660 -6.13673 1.17217 -0.00984212 -0.002147 -0.00598785 0.98456 0.174931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.93423e-06 0.00871685 3.99986 0.025051 0.122585 +EDGE_SE3:QUAT 661 662 4.19942 -0.351946 -0.0333441 0.00368072 0.0081381 -0.0429245 0.999038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 5.29999e-05 0.0668339 3.99972 -0.0014416 3.99375 +EDGE_SE3:QUAT 508 661 6.38584 -0.581369 -0.00397777 -0.00459554 0.00878862 -0.998577 0.0524075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000148925 -0.0184498 3.99993 0.0368365 0.0114116 +EDGE_SE3:QUAT 509 661 2.15619 -0.685856 -0.010582 0.00382022 0.00632125 -0.999681 0.0241581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 9.49576e-05 0.0152957 4.0001 0.0245119 0.00254326 +EDGE_SE3:QUAT 510 661 -2.07092 -0.511477 -0.0021482 -0.0058319 -0.00376398 0.998299 0.0578896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000123651 0.0234393 4.00042 0.0176247 0.0136205 +EDGE_SE3:QUAT 511 661 -6.28851 0.671354 0.0415862 -0.00192493 -0.00228135 0.983672 0.179946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.74059e-05 0.00795828 4 0.0110765 0.12957 +EDGE_SE3:QUAT 662 663 3.99399 -0.144855 0.00109267 0.00263294 -0.00178402 -0.00779596 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.89343e-05 -0.0140246 3.99999 5.45431e-05 3.99981 +EDGE_SE3:QUAT 507 662 6.42984 -0.787063 0.0533958 0.00610768 0.00846194 -0.99989 0.0105276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000203053 0.0244369 4.00034 0.0333299 0.000870342 +EDGE_SE3:QUAT 508 662 2.18305 -0.670766 0.00530311 0.00336253 0.00540788 -0.999935 0.00941435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.22888e-05 0.0134524 4.00007 0.0213746 0.00051399 +EDGE_SE3:QUAT 509 662 -2.07165 -0.548543 -0.0718631 -0.0117055 -0.00299109 0.999736 0.0195462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99946 0.000202329 0.0468466 4.00212 0.0137932 0.00212468 +EDGE_SE3:QUAT 510 662 -6.19184 0.298013 -0.0840949 -0.0134543 0.000110066 0.994807 0.100888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 0.000425524 0.0546306 4.00282 0.0103324 0.0414942 +EDGE_SE3:QUAT 663 664 4.29818 -0.142946 0.0310757 0.00395999 0.00603398 -0.00454363 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 9.21918e-05 0.0484914 3.99985 -0.000106883 4.00051 +EDGE_SE3:QUAT 506 663 6.81099 -0.848946 -0.0335198 -0.00231431 0.00901932 -0.999955 0.0015555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.26711e-05 -0.00925839 3.99976 0.0361054 0.000357025 +EDGE_SE3:QUAT 507 663 2.43976 -0.722718 0.00669976 0.00416871 0.0060353 -0.999969 0.00293146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000100273 0.0166758 4.00014 0.0240448 0.000248426 +EDGE_SE3:QUAT 508 663 -1.81224 -0.606274 -0.0183207 0.00127764 0.00269759 -0.999995 0.00139977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.38126e-05 0.00511064 4 0.0107761 4.3398e-05 +EDGE_SE3:QUAT 509 663 -6.0546 -0.256279 -0.170583 -0.00974207 -0.000790308 0.999575 0.0274513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 9.27997e-05 0.0390106 4.0015 0.00529617 0.00340208 +EDGE_SE3:QUAT 664 665 4.39224 -0.12161 0.0346396 0.000103574 -0.00838345 -0.00409074 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00112 -1.03776e-05 -0.0670773 3.99972 0.000137469 4.00106 +EDGE_SE3:QUAT 505 664 7.12211 -0.855491 0.0622533 -0.0114187 -0.00458074 0.999907 0.0058279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.00022675 0.0456759 4.00199 0.0188671 0.000746441 +EDGE_SE3:QUAT 506 664 2.56699 -0.73739 0.0229163 -0.00373041 -0.00485795 0.999975 0.00347317 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.29892e-05 0.0149223 4.00013 0.0195361 0.000199332 +EDGE_SE3:QUAT 507 664 -1.77881 -0.621796 0.00398642 -0.0101314 -0.00217834 0.999944 0.00202394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 9.33105e-05 0.0405242 4.00162 0.00888234 0.000446694 +EDGE_SE3:QUAT 508 664 -6.05354 -0.494924 0.00296069 -0.00750934 0.00120268 0.999967 0.00289011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 -3.22701e-05 0.0300369 4.0009 -0.00463843 0.000264357 +EDGE_SE3:QUAT 665 666 4.25835 -0.108702 0.0244924 -0.00246371 -0.00396 -0.00342539 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 3.79031e-05 -0.0317822 3.99994 5.35677e-05 4.00021 +EDGE_SE3:QUAT 504 665 6.78274 -0.796096 0.0558201 -0.00898989 -0.00502208 0.999868 0.0125895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000202205 0.0359683 4.00116 0.0209946 0.00106764 +EDGE_SE3:QUAT 505 665 2.69374 -0.677119 -0.000753665 -0.00274938 -0.00481811 0.999936 0.00986792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.28657e-05 0.0109995 4.00002 0.0194853 0.000514681 +EDGE_SE3:QUAT 506 665 -1.84621 -0.585039 0.0297107 0.0044811 -0.00487215 0.999951 0.00740296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -8.51129e-05 -0.0179263 4.00023 0.0192225 0.000391931 +EDGE_SE3:QUAT 507 665 -6.14254 -0.486765 -0.0533746 -0.00221449 -0.00214914 0.999976 0.0061715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.95248e-05 0.0088585 4.00006 0.00870527 0.000190914 +EDGE_SE3:QUAT 666 667 4.36453 -0.109372 0.00330766 -0.0010044 -0.0043738 -0.00310641 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 1.6173e-05 -0.0350297 3.99992 5.39763e-05 4.00027 +EDGE_SE3:QUAT 503 666 6.80123 -0.692328 0.0872393 -0.0103234 -0.00550081 0.999747 0.0192006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000270577 0.0413164 4.00153 0.0235814 0.00204059 +EDGE_SE3:QUAT 504 666 2.49419 -0.580167 0.00296559 -0.0048928 -0.007759 0.999828 0.0161276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000152752 0.0195802 4.00011 0.0316499 0.00138674 +EDGE_SE3:QUAT 505 666 -1.55332 -0.488638 0.0024425 0.00127548 -0.00741961 0.999883 0.0132807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.30703e-05 -0.00510387 3.99981 0.0295294 0.000930069 +EDGE_SE3:QUAT 506 666 -6.12774 -0.412562 0.0945535 0.00848316 -0.00735668 0.999879 0.0107926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000235429 -0.0339399 4.00097 0.0286966 0.000959778 +EDGE_SE3:QUAT 667 668 4.57315 -0.111525 -0.00199875 -9.14239e-05 0.00926155 -0.00139919 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00137 -6.27238e-06 0.0741129 3.99966 -5.20837e-05 4.00136 +EDGE_SE3:QUAT 502 667 6.79123 -0.532617 -0.00917156 0.00193462 -0.00535841 0.999691 0.0242145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.44522e-05 -0.00774621 3.99996 0.0210279 0.00247099 +EDGE_SE3:QUAT 503 667 2.46206 -0.41826 0.00266579 -0.00586608 -0.00688606 0.999715 0.0220786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000170234 0.0234824 4.00032 0.0285507 0.00229163 +EDGE_SE3:QUAT 504 667 -1.81106 -0.33778 -0.0303677 -0.000489531 -0.0089631 0.999774 0.0192865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.18031e-06 0.00195883 3.99968 0.0358932 0.00181106 +EDGE_SE3:QUAT 505 667 -5.89422 -0.271411 0.022711 0.00575044 -0.00851417 0.999815 0.0162893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.000191594 -0.0230131 4.00028 0.0332901 0.00147091 +EDGE_SE3:QUAT 668 669 4.43861 -0.0977645 0.0375244 -0.00166094 0.00798655 -0.000585713 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -5.39914e-05 0.0638947 3.99974 -2.1266e-05 4.00102 +EDGE_SE3:QUAT 501 668 6.69216 -0.298513 -0.0428719 0.00296322 -0.0043285 0.999639 0.026336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.91337e-05 -0.0118661 4.00008 0.0166608 0.00287901 +EDGE_SE3:QUAT 502 668 2.2311 -0.20161 0.0147042 -0.00729202 -0.00543743 0.999627 0.0257472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.00018377 0.0291973 4.00068 0.0232209 0.00299979 +EDGE_SE3:QUAT 503 668 -2.13085 -0.103876 -0.0554949 -0.0152001 -0.00691329 0.999589 0.0232867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99912 0.000538186 0.0608488 4.00338 0.0304836 0.00332752 +EDGE_SE3:QUAT 504 668 -6.41667 -0.0459194 -0.0306142 -0.0097397 -0.0089976 0.999703 0.0204652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000381903 0.0389865 4.00111 0.0375639 0.00240821 +EDGE_SE3:QUAT 669 670 4.16505 -0.0842952 0.0474934 1.78859e-05 -0.0021289 0.000115467 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.39761e-07 -0.0170315 3.99998 -9.81389e-07 4.00007 +EDGE_SE3:QUAT 500 669 6.43823 -0.0600623 0.0090986 -0.00524939 -0.00544202 0.99959 0.0276236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.00012463 0.0210215 4.00028 0.0228886 0.00329385 +EDGE_SE3:QUAT 501 669 2.25567 0.028232 0.0199848 -0.00483755 -0.00598831 0.999612 0.0267687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000121933 0.0193711 4.00019 0.0249481 0.00311583 +EDGE_SE3:QUAT 502 669 -2.18632 0.117275 -0.0128762 -0.0151391 -0.00684256 0.999518 0.0262364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 0.000545505 0.0606181 4.00334 0.0305361 0.00390579 +EDGE_SE3:QUAT 503 669 -6.5346 0.192649 -0.145532 -0.0231532 -0.00849804 0.999413 0.0237841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99794 0.00107819 0.0926831 4.00806 0.0384596 0.00478131 +EDGE_SE3:QUAT 670 671 4.14626 -0.0922353 0.0152317 0.000776223 -0.00344441 0.000523105 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -1.05498e-05 -0.0275613 3.99995 -6.98895e-06 4.00019 +EDGE_SE3:QUAT 499 670 6.4931 0.202172 0.0487132 -0.00713999 -0.00765253 0.99965 0.0242882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000234949 0.0285866 4.00052 0.031959 0.00281952 +EDGE_SE3:QUAT 500 670 2.28755 0.254343 0.0129097 -0.00308067 -0.00562546 0.99961 0.0271907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.78285e-05 0.012336 4 0.0231306 0.00312926 +EDGE_SE3:QUAT 501 670 -1.84523 0.344127 0.0195841 -0.00277046 -0.00621192 0.999622 0.0266312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.47636e-05 0.0110933 3.99995 0.0253939 0.00302899 +EDGE_SE3:QUAT 502 670 -6.36428 0.431392 -0.0993173 -0.0131594 -0.00710255 0.999558 0.0257091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99935 0.000467177 0.0526903 4.00245 0.0310963 0.0035801 +EDGE_SE3:QUAT 671 672 4.07386 -0.0949113 0.0010512 0.00186512 0.00366957 0.000774351 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 2.76101e-05 0.0293405 3.99995 1.19615e-05 4.00021 +EDGE_SE3:QUAT 498 671 6.89939 0.446383 0.0347847 -0.00233901 -0.00798483 0.999795 0.0184421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.73227e-05 0.00936124 3.99982 0.0322569 0.00164258 +EDGE_SE3:QUAT 499 671 2.34733 0.487044 0.0102817 -0.00364641 -0.0068503 0.999696 0.0234193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.77414e-05 0.0145979 4 0.0280476 0.00244393 +EDGE_SE3:QUAT 500 671 -1.79169 0.565052 0.000341047 0.000385619 -0.00489376 0.999629 0.0268053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.24849e-05 -0.00154497 3.99991 0.019457 0.00296941 +EDGE_SE3:QUAT 501 671 -5.98645 0.658862 0.018958 0.000499872 -0.00537097 0.999646 0.0260614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.64619e-05 -0.0020024 3.99989 0.021343 0.00283176 +EDGE_SE3:QUAT 672 673 4.02767 -0.0844143 0.0304322 -0.000821515 -0.000251242 0.000838039 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.22331e-07 -0.00200167 4 -8.38822e-07 4 +EDGE_SE3:QUAT 497 672 6.85313 0.708572 0.0301277 -0.00562194 -0.00558692 0.999943 0.00720963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000129248 0.0224903 4.00037 0.0226725 0.000462876 +EDGE_SE3:QUAT 498 672 2.81107 0.678027 0.0180535 -0.00589259 -0.00607905 0.999808 0.017649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000152116 0.0235822 4.00038 0.0251331 0.00154297 +EDGE_SE3:QUAT 499 672 -1.6999 0.762086 -0.0204382 -0.0071496 -0.00511837 0.999698 0.0229313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000168552 0.0286212 4.00067 0.0217631 0.00242672 +EDGE_SE3:QUAT 500 672 -5.87072 0.889328 0.0105683 -0.00328275 -0.00325545 0.999655 0.0258425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.67871e-05 0.0131439 4.00012 0.013679 0.00276136 +EDGE_SE3:QUAT 673 674 4.16537 -0.0711542 0.0520549 -0.0013505 -0.00697266 0.00418274 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 4.25016e-05 -0.0557213 3.99981 -0.000118118 4.00071 +EDGE_SE3:QUAT 496 673 7.09645 1.02652 0.0194952 0.00848344 0.00289028 -0.99982 0.0167183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 6.9983e-05 0.0339471 4.00114 0.0104227 0.00143337 +EDGE_SE3:QUAT 497 673 2.82232 0.861121 0.0203289 -0.00510858 -0.00649452 0.999948 0.006058 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000134419 0.0204365 4.00024 0.0262264 0.00042316 +EDGE_SE3:QUAT 498 673 -1.13004 0.915666 0.00245153 -0.00561606 -0.00696276 0.999818 0.0168611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000161977 0.022475 4.00028 0.0285926 0.00146791 +EDGE_SE3:QUAT 499 673 -5.61511 1.05533 -0.0514954 -0.00733189 -0.00598164 0.999702 0.0225192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000196714 0.0293505 4.00067 0.0252231 0.00240302 +EDGE_SE3:QUAT 674 675 4.38809 -0.125355 0.0327853 -0.00447557 0.00110472 -0.0225009 0.999736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -1.66773e-05 0.00762278 4 -8.13071e-05 3.99799 +EDGE_SE3:QUAT 495 674 6.99661 1.42199 -0.0103441 0.00184307 0.00100383 -0.99745 0.0713372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.60156e-06 0.00743124 4.00006 0.00291789 0.020372 +EDGE_SE3:QUAT 496 674 2.93819 0.948156 0.00511478 0.00165117 0.00437105 -0.999769 0.0209571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.04937e-05 0.00660954 3.99997 0.0171884 0.00184162 +EDGE_SE3:QUAT 497 674 -1.31754 0.990427 0.0349709 0.00166672 -0.00825607 0.999963 0.00188014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.59337e-05 -0.0066676 3.99977 0.0329983 0.000297491 +EDGE_SE3:QUAT 498 674 -5.22183 1.14622 0.0109076 0.00078759 -0.00882443 0.999872 0.0133034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.58002e-05 -0.0031518 3.9997 0.0351971 0.00102019 +EDGE_SE3:QUAT 675 676 4.29699 -0.345659 -0.0229563 -0.000507315 0.00975752 -0.075626 0.997088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00148 -0.000188947 0.0769575 3.99964 -0.00289973 3.9786 +EDGE_SE3:QUAT 494 675 6.39892 1.86641 -0.021782 -0.00612383 0.00207647 -0.987487 0.157566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000161769 -0.0253263 4.00045 0.0153253 0.0995318 +EDGE_SE3:QUAT 495 675 2.6224 0.920075 0.00130829 0.00276837 0.0055944 -0.998783 0.0489274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.27464e-05 0.0111188 4.00004 0.0211636 0.00971881 +EDGE_SE3:QUAT 496 675 -1.45212 0.900621 0.0140832 -0.00294544 -0.00877152 0.999955 0.00192554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.00010255 0.0117832 3.99983 0.0351314 0.000358105 +EDGE_SE3:QUAT 497 675 -5.70107 1.1549 0.0861023 0.000607957 -0.0127904 0.999615 0.0245986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.26792e-05 -0.00243655 3.99936 0.0509608 0.0030716 +EDGE_SE3:QUAT 676 677 4.2113 -0.728954 0.00995351 0.000211988 -0.00101133 -0.175632 0.984455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.46254e-06 -0.00728159 4 0.000615167 3.87663 +EDGE_SE3:QUAT 493 676 5.90674 1.9102 0.0428296 0.00476485 0.00635357 -0.974292 0.225148 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -2.70695e-05 0.0210318 4.00051 0.0141062 0.20294 +EDGE_SE3:QUAT 494 676 2.22912 0.847722 0.0115288 0.00356627 0.00357959 -0.996589 0.0823694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.89228e-05 0.0144255 4.0002 0.0117429 0.0272261 +EDGE_SE3:QUAT 495 676 -1.66317 0.830781 -0.042809 -0.0123125 -0.00686 0.999544 0.0267183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99943 0.000421754 0.0493031 4.00213 0.0300448 0.0036893 +EDGE_SE3:QUAT 496 676 -5.71492 1.26686 -0.0169737 -0.012259 -0.00966169 0.99689 0.0772484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000649004 0.0494469 4.00157 0.0456325 0.0250066 +EDGE_SE3:QUAT 677 678 3.97195 -0.942201 0.00103608 0.00201935 -0.00213136 -0.219871 0.975524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.07769e-05 -0.0106732 4 0.000931532 3.80665 +EDGE_SE3:QUAT 492 677 5.61379 1.61906 0.0422602 0.00619767 0.00912016 -0.982109 0.18799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 4.6239e-05 0.0265529 4.00079 0.0243131 0.141703 +EDGE_SE3:QUAT 493 677 1.79824 0.721436 0.00980351 0.00242615 0.0063557 -0.998699 0.0505457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.82073e-05 0.0097488 3.99997 0.0242826 0.0103911 +EDGE_SE3:QUAT 494 677 -2.03507 0.87582 -0.0084619 -0.0018335 -0.00314983 0.995573 0.093917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.0165e-05 0.00740962 3.99999 0.0136879 0.0353427 +EDGE_SE3:QUAT 495 677 -5.81747 1.78574 -0.123677 -0.0100557 -0.00817063 0.979261 0.202188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000488515 0.0420826 4.0005 0.0450035 0.164497 +EDGE_SE3:QUAT 678 679 3.99543 -0.898379 -0.00538457 0.0008601 0.00425954 -0.197569 0.980279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -7.31235e-05 0.034089 3.99994 -0.00336721 3.84416 +EDGE_SE3:QUAT 491 678 5.63387 1.87211 0.0242063 0.00391567 0.00734421 -0.994613 0.10332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000100796 0.0159768 4.00018 0.0253963 0.0429282 +EDGE_SE3:QUAT 492 678 1.56584 1.04233 -0.00580889 -0.00230107 -0.00797206 0.999434 0.032588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.97693e-05 0.00921751 3.9998 0.0324025 0.00453194 +EDGE_SE3:QUAT 493 678 -2.22828 1.24969 -0.00199273 0.00111786 -0.0045988 0.985329 0.170599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.15516e-05 -0.00484514 3.99999 0.0155894 0.116485 +EDGE_SE3:QUAT 494 678 -5.75437 2.53845 -0.0154284 0.00129746 -0.00203534 0.95053 0.310623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.55599e-06 -0.00637304 4.00005 0.00333223 0.385961 +EDGE_SE3:QUAT 679 680 4.07786 -0.654067 0.000355072 -0.00129337 0.00510296 -0.15204 0.98836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -0.000106073 0.0370955 3.99993 -0.00272514 3.90788 +EDGE_SE3:QUAT 490 679 5.18299 3.0088 -0.0304992 -0.00204323 0.00652292 -0.997493 0.0704308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.26506e-05 -0.00821569 3.99986 0.0269139 0.0200409 +EDGE_SE3:QUAT 491 679 1.5433 1.9222 -0.00289245 -0.00681353 -0.00706117 0.995382 0.0954891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000232777 0.027578 4.00032 0.0327659 0.0369347 +EDGE_SE3:QUAT 492 679 -2.33044 2.16115 -0.0125589 -0.0049254 -0.00710104 0.973239 0.229634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.79106e-05 0.0205111 3.99986 0.0333007 0.211326 +EDGE_SE3:QUAT 493 679 -5.66361 3.4221 0.019104 -0.00203113 -0.00282785 0.93232 0.361616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.53509e-06 0.00848601 3.99996 0.0128953 0.523132 +EDGE_SE3:QUAT 680 681 4.10772 -0.881162 0.00782244 0.00231413 0.00170149 -0.20348 0.979075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.07755e-07 0.0182702 3.99998 -0.00202052 3.83447 +EDGE_SE3:QUAT 489 680 3.59696 4.08999 -0.00923039 0.000296002 0.00579805 -0.987528 0.157339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.15466e-05 0.00140804 3.99991 0.0214059 0.0991406 +EDGE_SE3:QUAT 490 680 1.08464 3.08204 -0.0100502 -0.00181829 -0.00757833 0.996616 0.0818281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.91949e-05 0.00731301 3.99978 0.0309886 0.0270384 +EDGE_SE3:QUAT 491 680 -2.31201 3.33852 -0.0480172 -0.0106544 -0.00887437 0.969193 0.245912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000517659 0.045262 4.00033 0.0499506 0.243073 +EDGE_SE3:QUAT 492 680 -5.67695 4.55895 -0.0305929 -0.00888752 -0.00795064 0.926853 0.375236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 0.000194204 0.0388778 3.99981 0.0441001 0.564152 +EDGE_SE3:QUAT 681 682 4.21349 -0.96053 0.000555213 -0.00494897 -0.00415649 -0.209856 0.977711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -2.00807e-05 -0.0431803 3.99988 0.00488488 3.82431 +EDGE_SE3:QUAT 487 681 4.309 5.00043 0.0212762 0.00448534 0.00445867 -0.917256 0.398248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000208655 0.0239301 4.00047 -0.000854944 0.634575 +EDGE_SE3:QUAT 488 681 1.88345 3.81306 -0.0239378 0.00512055 0.00111659 -0.980815 0.194869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000103075 0.0216813 4.00042 -0.0036324 0.152021 +EDGE_SE3:QUAT 489 681 -0.542538 3.6796 0.000411616 -0.000928221 -0.00348016 0.998934 0.0460271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.01503e-06 0.00372201 3.99996 0.014188 0.00852786 +EDGE_SE3:QUAT 490 681 -2.8117 4.61244 -0.000355845 -0.0017321 -0.00492625 0.959079 0.283091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.4481e-05 0.0068159 3.9999 0.0194778 0.320678 +EDGE_SE3:QUAT 682 683 4.14518 -0.73984 -0.00516029 -0.00265425 0.000294523 -0.149117 0.988816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.23411e-06 -0.00240108 4 0.000299016 3.91106 +EDGE_SE3:QUAT 486 682 4.2694 2.84538 0.0213542 -0.000198471 0.0105893 -0.954944 0.296599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000166842 0.00131997 3.99981 0.0337636 0.352208 +EDGE_SE3:QUAT 487 682 0.731011 2.5689 -0.0227217 -0.00261902 0.00810716 -0.980368 0.196994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.1405e-05 -0.0105723 3.99973 0.0332916 0.155543 +EDGE_SE3:QUAT 488 682 -2.3731 3.12067 -0.0681057 0.000178699 -0.00624979 0.999865 0.0151822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.17798e-06 -0.000715288 3.99985 0.0249626 0.00107794 +EDGE_SE3:QUAT 489 682 -4.6354 5.02186 0.00241252 0.00347631 -0.00885176 0.966824 0.255266 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -5.22048e-05 -0.0163739 4.00033 0.0231393 0.260867 +EDGE_SE3:QUAT 603 682 3.18274 3.42158 0.0661101 0.00269279 0.0141317 -0.86912 0.494391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000332453 0.0275943 4.00096 0.017069 0.978157 +EDGE_SE3:QUAT 604 682 -2.32335 3.61182 0.0458559 0.0004262 0.0135421 -0.776323 0.63019 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000488839 0.029485 4.00074 0.00735003 1.58908 +EDGE_SE3:QUAT 683 684 3.96744 -0.519141 0.00751576 0.00530465 0.0187492 -0.104039 0.994382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00583 -0.000507964 0.154339 3.99855 -0.00808485 3.96265 +EDGE_SE3:QUAT 485 683 4.57197 1.10069 -0.0138852 -0.0047752 0.0122811 -0.98423 0.1764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.90061e-05 -0.0194343 3.99941 0.0518699 0.125257 +EDGE_SE3:QUAT 486 683 0.446663 1.10845 0.00231007 -0.00232327 0.0131321 -0.988453 0.150939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.98113e-05 -0.0092435 3.9993 0.0522971 0.0918523 +EDGE_SE3:QUAT 487 683 -3.36727 1.63545 -0.0106184 -0.00389572 0.0104438 -0.998751 0.0487031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000132184 -0.0156309 3.99972 0.0430419 0.0100134 +EDGE_SE3:QUAT 602 683 4.68602 -0.366027 -0.0156115 -0.00451468 0.0127349 -0.97058 0.240398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.78591e-05 -0.01814 3.99931 0.0519058 0.231963 +EDGE_SE3:QUAT 603 683 0.436259 0.243312 -0.0016759 -0.000406165 0.0168569 -0.933101 0.35922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99958 0.000389624 0.00434645 3.9998 0.047706 0.516876 +EDGE_SE3:QUAT 604 683 -3.88575 -0.289669 -0.022063 -0.00288984 0.015702 -0.861698 0.50717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 0.000290958 0.00130201 3.99994 0.034992 1.02946 +EDGE_SE3:QUAT 684 685 4.22276 -0.431469 0.0221884 0.00474609 -0.00115431 -0.0662586 0.997791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -1.07778e-05 -0.00541093 4 0.000136982 3.98245 +EDGE_SE3:QUAT 484 684 4.82177 0.162973 0.0532573 0.00929085 0.00994775 -0.996715 0.0798311 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 0.000230625 0.0375574 4.00133 0.0332794 0.0261262 +EDGE_SE3:QUAT 485 684 0.686944 0.234173 0.0208557 0.0132675 0.00973594 -0.997169 0.0733723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99917 0.000220946 0.0535234 4.00286 0.0307047 0.0224916 +EDGE_SE3:QUAT 486 684 -3.46488 0.419166 0.030074 0.0155664 0.0101118 -0.998707 0.0473156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99893 0.000373326 0.0624782 4.00381 0.0343873 0.0102296 +EDGE_SE3:QUAT 601 684 5.05094 -2.12793 0.0335745 0.00848894 0.0125006 -0.996455 0.0827587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99957 0.000337681 0.034362 4.00095 0.0435853 0.0281722 +EDGE_SE3:QUAT 602 684 0.957427 -1.75464 0.0173245 0.0135469 0.0111893 -0.990312 0.137743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99903 -3.23395e-05 0.0559319 4.00331 0.0280323 0.076895 +EDGE_SE3:QUAT 603 684 -2.83266 -2.01086 -0.0213511 0.0172402 0.0182647 -0.965208 0.260276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99818 -0.0011511 0.0781377 4.00664 0.0275537 0.272862 +EDGE_SE3:QUAT 604 684 -6.24935 -3.50185 -0.0503939 0.0144636 0.0197 -0.909598 0.41477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 -0.00255195 0.0819644 4.00602 0.00725546 0.69024 +EDGE_SE3:QUAT 685 686 4.512 -0.221446 0.00369304 0.00473773 -0.00962538 -0.0177283 0.999785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00135 -0.000217946 -0.0759802 3.99964 0.00068137 4.00019 +EDGE_SE3:QUAT 483 685 4.83082 -0.15542 0.0511301 0.00976884 0.0100004 -0.999788 0.015112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000367286 0.0390922 4.0012 0.038817 0.00167227 +EDGE_SE3:QUAT 484 685 0.600716 -0.0939973 0.00215178 0.00787711 0.00567054 -0.999864 0.0133096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000161915 0.0315172 4.00089 0.0218408 0.00107621 +EDGE_SE3:QUAT 485 685 -3.50776 0.0552524 -0.0607316 0.011984 0.00583402 -0.999889 0.0065849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99942 0.000259099 0.0479378 4.00218 0.0227198 0.000877008 +EDGE_SE3:QUAT 600 685 4.82439 -2.50168 0.029402 0.00664652 0.00821699 -0.999931 0.00514075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.0002158 0.0265891 4.00045 0.0325994 0.000548101 +EDGE_SE3:QUAT 601 685 0.826243 -2.40338 -0.0131273 0.0071656 0.00843893 -0.999808 0.0161654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000230306 0.0286759 4.00058 0.0328157 0.00152015 +EDGE_SE3:QUAT 602 685 -3.19283 -2.49128 -0.0792595 0.0122974 0.00724897 -0.997356 0.0712549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 0.000101442 0.0495799 4.00248 0.0216716 0.0210451 +EDGE_SE3:QUAT 686 687 4.00303 -0.108267 -0.0147225 -0.000988761 0.00135917 -0.00303892 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.48588e-06 0.0108372 3.99999 -1.64923e-05 3.99999 +EDGE_SE3:QUAT 482 686 4.65093 -0.183229 -0.0204719 0.00447072 -0.00692186 0.999948 0.0059622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000123161 -0.0178849 4.00014 0.0274742 0.000410864 +EDGE_SE3:QUAT 483 686 0.348015 -0.0788542 -0.0302298 -4.23607e-05 -0.00550552 0.999981 0.00280613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.52401e-07 0.000169448 3.99988 0.0220223 0.000152755 +EDGE_SE3:QUAT 484 686 -3.87132 0.0299828 -0.0693496 0.00167352 -0.00132572 0.999987 0.00456851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.629e-06 -0.00669428 4.00004 0.00524153 0.000101557 +EDGE_SE3:QUAT 599 686 4.61469 -2.40405 -0.000873111 0.00187713 -0.00239578 0.999915 0.0127005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.74521e-05 -0.00751041 4.00004 0.00938874 0.00068135 +EDGE_SE3:QUAT 600 686 0.330993 -2.3419 -0.0239759 0.00306679 -0.00360055 0.99991 0.0125169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.25354e-05 -0.0122703 4.00011 0.0140902 0.000713981 +EDGE_SE3:QUAT 601 686 -3.66521 -2.31209 -0.0728812 0.00241447 -0.00386899 0.999989 0.00133567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.73403e-05 -0.00965809 4.00003 0.0154505 9.01342e-05 +EDGE_SE3:QUAT 687 688 4.02078 -0.100307 0.0321037 -0.000533433 0.00689093 0.0005015 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 -1.41426e-05 0.0551398 3.99981 1.32253e-05 4.00076 +EDGE_SE3:QUAT 481 687 4.96328 -0.168721 -0.0117486 -1.15009e-05 -0.00635956 0.999822 0.0177907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.45678e-06 4.57052e-05 3.99984 0.0254192 0.00142763 +EDGE_SE3:QUAT 482 687 0.662782 -0.0395848 0.000594611 0.00326097 -0.00768905 0.999923 0.00922139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00010217 -0.0130467 3.99994 0.0305101 0.000615429 +EDGE_SE3:QUAT 483 687 -3.6092 0.0614806 -0.0460024 -0.0013975 -0.00626532 0.999961 0.00599764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.33992e-05 0.00559062 3.99987 0.0251258 0.000309538 +EDGE_SE3:QUAT 598 687 5.09309 -2.30877 -0.0035242 -0.00030236 -0.00285454 0.999864 0.0162498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.41539e-06 0.00120983 3.99997 0.0114499 0.00108938 +EDGE_SE3:QUAT 599 687 0.618349 -2.2104 -0.00451261 0.000420732 -0.00356545 0.999867 0.0159272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.52623e-06 -0.00168372 3.99995 0.0141991 0.00106584 +EDGE_SE3:QUAT 600 687 -3.62542 -2.13167 -0.0112414 0.00150092 -0.00461311 0.999858 0.0161377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.94522e-05 -0.00600637 3.99996 0.0182468 0.00113398 +EDGE_SE3:QUAT 688 689 4.5001 -0.0988997 0.0506178 -0.000747905 -0.00173275 0.00336516 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 5.41043e-06 -0.0138317 3.99999 -2.33103e-05 4 +EDGE_SE3:QUAT 480 688 4.99715 -0.0345627 0.0648716 -0.0127757 -0.00509321 0.999659 0.0222143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99937 0.000341183 0.051139 4.00244 0.0226371 0.00275616 +EDGE_SE3:QUAT 481 688 0.94846 0.0709985 0.0232288 -0.00685526 -0.00669902 0.999802 0.0174137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000196288 0.0274347 4.00053 0.0277367 0.00159352 +EDGE_SE3:QUAT 482 688 -3.3631 0.132919 0.0535973 -0.00379183 -0.0082976 0.999917 0.00904986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000123833 0.0151706 3.99994 0.0334595 0.000665045 +EDGE_SE3:QUAT 597 688 5.16508 -2.18379 0.0691601 -0.012016 -0.00144668 0.999751 0.0187738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99943 0.000134023 0.0480862 4.00228 0.00759202 0.00200258 +EDGE_SE3:QUAT 598 688 1.07657 -2.07626 0.0248117 -0.0072154 -0.00329379 0.999845 0.0156908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000112996 0.0288721 4.00077 0.0140765 0.0012428 +EDGE_SE3:QUAT 599 688 -3.39445 -1.97321 0.0393558 -0.00649198 -0.00391759 0.999846 0.0158394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000115452 0.0259778 4.00059 0.0164866 0.00124025 +EDGE_SE3:QUAT 689 690 4.49662 -0.0772948 0.0227566 -0.00268045 -0.00467466 0.00364233 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 5.18257e-05 -0.0372818 3.99991 -6.92391e-05 4.00029 +EDGE_SE3:QUAT 479 689 4.63853 0.212691 0.0549651 -0.0116025 -0.00505404 0.999828 0.0135747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.000275383 0.0464219 4.00201 0.0214822 0.00139131 +EDGE_SE3:QUAT 480 689 0.506682 0.251751 0.0116903 -0.0111573 -0.00571896 0.999743 0.0188682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 0.000305626 0.0446531 4.0018 0.0245553 0.00207343 +EDGE_SE3:QUAT 481 689 -3.51192 0.32012 0.0258448 -0.00540917 -0.00722379 0.999855 0.0144165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.00015993 0.0216448 4.00023 0.0295076 0.00116619 +EDGE_SE3:QUAT 596 689 4.83768 -2.02004 0.0646806 -0.0116211 -0.00255202 0.999814 0.0151481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 0.000166733 0.0464979 4.00211 0.011619 0.00149229 +EDGE_SE3:QUAT 597 689 0.668212 -1.91594 0.0158862 -0.0105261 -0.00223335 0.999827 0.0151548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000133531 0.0421173 4.00174 0.0102105 0.00138833 +EDGE_SE3:QUAT 598 689 -3.40925 -1.84219 0.0257855 -0.00566115 -0.00367552 0.999901 0.0123797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 9.12439e-05 0.0226499 4.00045 0.0152596 0.000799517 +EDGE_SE3:QUAT 690 691 4.44024 -0.0873453 -0.0317372 0.00116957 0.00294094 0.00395153 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.45337e-05 0.0234722 3.99997 4.65847e-05 4.00008 +EDGE_SE3:QUAT 478 690 4.60464 0.381888 -0.0180112 -0.00546397 0.00639427 -0.999961 0.00262132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000140804 -0.0218571 4.00031 0.0256949 0.000311958 +EDGE_SE3:QUAT 479 690 0.162244 0.408308 -0.0198897 -0.00698649 -0.00776165 0.999896 0.00993151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.00022353 0.0279521 4.00051 0.0316013 0.000839526 +EDGE_SE3:QUAT 480 690 -3.96534 0.510114 -0.063662 -0.00666754 -0.00862906 0.999822 0.0153778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000236617 0.0266821 4.00037 0.0353228 0.00143587 +EDGE_SE3:QUAT 595 690 4.56978 -1.86585 -0.0307098 0.00640548 -0.00501331 0.999943 0.00689305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000123019 -0.0256241 4.00057 0.0197019 0.000451244 +EDGE_SE3:QUAT 596 690 0.36792 -1.79852 -0.0110079 -0.00692449 -0.00541484 0.999896 0.0113929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000160196 0.027704 4.00063 0.0222888 0.00083529 +EDGE_SE3:QUAT 597 690 -3.79832 -1.6991 -0.0493455 -0.00598333 -0.00493803 0.999901 0.011771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.00012579 0.0239388 4.00046 0.0203123 0.000800661 +EDGE_SE3:QUAT 691 692 4.45115 -0.0951842 -0.0190907 0.00249503 0.00491199 0.00444881 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 5.13773e-05 0.0391645 3.9999 8.8477e-05 4.0003 +EDGE_SE3:QUAT 477 691 4.52634 0.405171 -0.0252964 -0.00758626 0.00680007 -0.999762 0.0193124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000224782 -0.0303633 4.00069 0.0283545 0.00192345 +EDGE_SE3:QUAT 478 691 0.179042 0.446752 -0.00042893 -0.0025422 0.00529805 -0.999961 0.00656284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.33837e-05 -0.0101698 3.99999 0.0213238 0.000311821 +EDGE_SE3:QUAT 479 691 -4.2622 0.593451 -0.114602 -0.0102378 -0.00659604 0.999908 0.00591295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000283153 0.040954 4.00148 0.0268809 0.000739765 +EDGE_SE3:QUAT 594 691 4.4365 -1.79538 -0.0365759 -0.00743445 0.00716552 -0.999946 0.00136297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.000214471 -0.0297394 4.00068 0.028751 0.000435148 +EDGE_SE3:QUAT 595 691 0.135467 -1.71793 -0.00579804 0.0035812 -0.00402596 0.999981 0.00285571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -5.71635e-05 -0.0143252 4.00014 0.0160227 0.000148103 +EDGE_SE3:QUAT 596 691 -4.05639 -1.60557 -0.109029 -0.00983389 -0.00433799 0.999914 0.00745258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 0.000186888 0.0393382 4.00146 0.0179452 0.000689563 +EDGE_SE3:QUAT 692 693 4.40588 -0.0877617 0.0280165 0.00190556 0.00535994 0.00479763 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 4.40246e-05 0.0427724 3.99989 0.000103853 4.00037 +EDGE_SE3:QUAT 476 692 4.57673 0.283542 0.0151758 0.00184295 0.00686902 -0.999297 0.0367963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.03535e-05 0.00739004 3.99989 0.0268414 0.00560992 +EDGE_SE3:QUAT 477 692 0.123505 0.331722 0.0238737 -0.00287031 0.00434231 -0.999705 0.0237066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.05259e-05 -0.0114908 4.00004 0.0178895 0.00236109 +EDGE_SE3:QUAT 478 692 -4.20771 0.490556 0.00316307 0.00248113 0.00265626 -0.999931 0.0111376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.52949e-05 0.00992646 4.00007 0.010401 0.000547871 +EDGE_SE3:QUAT 593 692 4.29627 -1.80257 0.0220081 0.00337006 0.00545257 -0.999929 0.0100645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.30407e-05 0.0134828 4.00007 0.0215345 0.00056657 +EDGE_SE3:QUAT 594 692 0.0345557 -1.71866 0.0222385 -0.00253179 0.00462937 -0.999969 0.00587458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.67552e-05 -0.010128 4.00001 0.0186353 0.000250508 +EDGE_SE3:QUAT 595 692 -4.3091 -1.59922 0.0114058 0.00134805 0.00163643 -0.999996 0.00165853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.78699e-06 0.00539226 4.00002 0.00652786 2.89252e-05 +EDGE_SE3:QUAT 693 694 4.41553 -0.0946027 0.0434271 0.000105842 -0.00620777 0.00416559 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 1.224e-06 -0.0496729 3.99985 -0.000103405 4.00055 +EDGE_SE3:QUAT 475 693 4.681 0.00365218 0.0690373 0.0131226 0.00530618 -0.998525 0.0524188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99927 6.2943e-05 0.0527074 4.0028 0.0156051 0.0117486 +EDGE_SE3:QUAT 476 693 0.22126 0.0556514 0.0289619 0.0074234 0.005206 -0.99911 0.0412053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000105041 0.0297717 4.00085 0.0182982 0.00709736 +EDGE_SE3:QUAT 477 693 -4.31831 0.210671 0.0777798 0.00279452 0.00256381 -0.999577 0.0288442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.43934e-05 0.0111925 4.00011 0.00959001 0.00338232 +EDGE_SE3:QUAT 592 693 4.37497 -1.88321 0.0474839 0.0119853 0.00760737 -0.999722 0.0188228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9994 0.000307174 0.0479666 4.00215 0.0286205 0.00219739 +EDGE_SE3:QUAT 593 693 -0.126407 -1.80538 0.0168611 0.0088035 0.00366085 -0.999849 0.0145514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000103109 0.0352244 4.00121 0.0136167 0.0012036 +EDGE_SE3:QUAT 594 693 -4.37859 -1.6802 0.0687371 0.00301621 0.00279566 -0.99994 0.0101645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.20936e-05 0.0120668 4.00012 0.010935 0.000479568 +EDGE_SE3:QUAT 694 695 4.20973 -0.0754135 0.0440337 -0.00170969 -0.00463194 0.00617285 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 3.4701e-05 -0.0369293 3.99991 -0.000114748 4.00019 +EDGE_SE3:QUAT 474 694 4.84903 -0.471934 0.0562436 0.0126939 0.0069236 -0.998019 0.0612369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99929 0.000119093 0.0510691 4.00262 0.021258 0.015768 +EDGE_SE3:QUAT 475 694 0.31242 -0.366831 0.000602182 0.00714939 0.0046998 -0.998326 0.0571947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 6.7693e-05 0.028744 4.00082 0.0153894 0.0133517 +EDGE_SE3:QUAT 476 694 -4.1752 -0.217865 0.0125146 0.00125735 0.00470897 -0.998925 0.0461063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.92376e-05 0.00504926 3.99995 0.0182731 0.00859321 +EDGE_SE3:QUAT 591 694 4.35126 -2.04295 0.0294768 0.0124316 0.00758254 -0.999553 0.0260922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99935 0.00028901 0.0497769 4.00236 0.0277085 0.00353511 +EDGE_SE3:QUAT 592 694 -0.0333339 -1.96184 -0.0110112 0.0059056 0.00741582 -0.999684 0.0232774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000164487 0.0236435 4.00039 0.028529 0.00251075 +EDGE_SE3:QUAT 593 694 -4.46864 -1.83612 -0.0103016 0.00292193 0.00320622 -0.999811 0.0189744 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.49341e-05 0.0116943 4.0001 0.0123705 0.00151258 +EDGE_SE3:QUAT 695 696 4.50543 -0.00823652 -0.00223271 -0.000323942 -0.00574875 0.0238833 0.999698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 2.62908e-05 -0.0458631 3.99987 -0.0005476 3.99824 +EDGE_SE3:QUAT 473 695 5.11347 -1.02794 0.0184586 0.0029291 0.00521304 -0.997943 0.0638281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.7698e-05 0.0117989 4.00008 0.0191514 0.0164232 +EDGE_SE3:QUAT 474 695 0.649666 -0.918897 -0.0125546 0.00787863 0.00837236 -0.997613 0.06809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.00018141 0.0317544 4.00092 0.0288404 0.0190074 +EDGE_SE3:QUAT 475 695 -3.82214 -0.765618 -0.0225889 0.00241823 0.00602089 -0.997945 0.0637431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.37416e-05 0.00974459 4 0.0226118 0.016405 +EDGE_SE3:QUAT 590 695 4.07132 -2.26734 -0.00868046 0.000243904 0.00615191 -0.999436 0.0330025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.57929e-05 0.000979091 3.99985 0.0244759 0.00450682 +EDGE_SE3:QUAT 591 695 0.104479 -2.19134 -0.0326287 0.00774449 0.00902326 -0.999399 0.0325737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000249315 0.0310316 4.00074 0.0339921 0.00477432 +EDGE_SE3:QUAT 592 695 -4.2403 -2.08145 -0.0178845 0.00127404 0.00881676 -0.999519 0.0297142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.15417e-05 0.00510548 3.99973 0.0348858 0.00384282 +EDGE_SE3:QUAT 696 697 4.21639 0.0402046 -0.00362035 -0.002826 0.00307393 0.042484 0.999088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -2.68401e-05 0.0259646 3.99996 0.000560627 3.99295 +EDGE_SE3:QUAT 472 696 4.84396 -1.80501 -0.027182 -0.00226783 0.00372317 -0.997492 0.070644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.20727e-05 -0.00912867 4 0.0159827 0.0200474 +EDGE_SE3:QUAT 473 696 0.641803 -1.60024 -0.0146241 -0.00256971 0.00497886 -0.996123 0.0877958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.18222e-05 -0.0103704 3.99996 0.0213238 0.0309739 +EDGE_SE3:QUAT 474 696 -3.78086 -1.50173 -0.0836723 0.00231732 0.00785062 -0.99578 0.0914085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.49078e-05 0.00943348 3.99993 0.0290688 0.0336578 +EDGE_SE3:QUAT 589 696 3.59194 -2.73533 -0.0180543 0.000887493 0.00306763 -0.999221 0.039339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.28202e-05 0.00355975 3.99998 0.0119442 0.00622913 +EDGE_SE3:QUAT 590 696 -0.421744 -2.56123 -0.011721 -0.00546243 0.00610668 -0.998337 0.0570657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.00015038 -0.0219485 4.00024 0.0267169 0.0133257 +EDGE_SE3:QUAT 591 696 -4.37889 -2.47634 -0.108863 0.00256631 0.00890228 -0.998336 0.0569199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000113282 0.0103293 3.99986 0.0341568 0.013279 +EDGE_SE3:QUAT 697 698 4.13372 0.178182 -0.00358606 0.00383666 0.0134963 0.0766332 0.996961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00262 0.00051111 0.103562 3.99937 0.00393389 3.97919 +EDGE_SE3:QUAT 471 697 4.61769 -3.02244 -0.0795792 -0.00892398 0.00655174 -0.999298 0.0357918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 -0.000285342 -0.035764 4.001 0.0286864 0.00565028 +EDGE_SE3:QUAT 472 697 0.682188 -2.43736 -0.0102229 0.000981571 0.00688779 -0.993533 0.113331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.9538e-05 0.00408183 3.99988 0.0257919 0.051549 +EDGE_SE3:QUAT 473 697 -3.48977 -2.37511 -0.00698586 0.000477922 0.00847482 -0.991466 0.13009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.02907e-05 0.00210952 3.99978 0.031984 0.0679554 +EDGE_SE3:QUAT 588 697 3.31782 -3.4962 -0.0477231 0.000453409 -0.00752434 0.999917 0.0104698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.83089e-05 -0.00181419 3.99978 0.0300503 0.000665086 +EDGE_SE3:QUAT 589 697 -0.597642 -3.11292 -0.0313395 0.00408207 0.0059926 -0.996611 0.0819429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 7.78962e-05 0.0165186 4.00022 0.0209131 0.0270375 +EDGE_SE3:QUAT 590 697 -4.60878 -3.07274 0.0229065 -0.00228819 0.00964369 -0.994984 0.0995384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.59111e-05 -0.0092123 3.99963 0.0394249 0.0400453 +EDGE_SE3:QUAT 698 699 4.04233 0.225677 0.022117 0.00296633 -0.00450389 0.091414 0.995798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -8.73693e-06 -0.0388192 3.9999 -0.00181574 3.96695 +EDGE_SE3:QUAT 470 698 3.13621 -4.38666 -0.0590441 -0.00243512 -0.00990735 0.997025 0.076396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.9866e-05 0.00979099 3.99963 0.0405303 0.0237825 +EDGE_SE3:QUAT 471 698 0.499685 -3.49181 -0.0136306 0.00520433 0.00400882 -0.993613 0.112648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 8.88241e-06 0.0212552 4.00047 0.0108999 0.0509035 +EDGE_SE3:QUAT 472 698 -3.32019 -3.52642 -0.0315342 0.0153191 0.00462479 -0.981818 0.189151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 -0.000842362 0.0647199 4.0039 -0.00550317 0.144205 +EDGE_SE3:QUAT 586 698 4.71886 -5.22987 -0.0480107 -0.00557215 -0.00977948 0.96831 0.249499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.06061e-05 0.0230579 3.99962 0.0435922 0.249639 +EDGE_SE3:QUAT 587 698 2.22493 -3.92878 -0.0532702 -0.00161091 -0.00876348 0.997147 0.0749546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.11445e-05 0.00646854 3.9997 0.0355217 0.0228005 +EDGE_SE3:QUAT 588 698 -0.837265 -3.5935 -0.0451841 0.0135408 0.00364635 -0.997686 0.0665233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99924 -9.95937e-05 0.0545243 4.003 0.00725544 0.0184614 +EDGE_SE3:QUAT 589 698 -4.65601 -3.94779 -0.0732873 0.0185412 0.00299497 -0.987226 0.158216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99877 -0.0011016 0.0769846 4.00547 -0.0116789 0.10168 +EDGE_SE3:QUAT 699 700 4.4381 0.403607 0.0174953 -0.000121477 -0.00196046 0.132565 0.991172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.25114e-05 -0.0150813 3.99999 -0.000986148 3.92976 +EDGE_SE3:QUAT 468 699 2.77505 -5.22054 -0.0478895 -5.07092e-05 -0.00375745 0.859158 0.511697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.72615e-07 -0.00376178 4.00003 0.00630419 1.04736 +EDGE_SE3:QUAT 469 699 1.15483 -4.11375 -0.0909606 -0.00106462 -0.0103356 0.966012 0.258287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000149989 0.0032369 3.99968 0.0366625 0.267216 +EDGE_SE3:QUAT 470 699 -0.894558 -3.97178 -0.0518828 -0.00130702 0.00660179 -0.999864 0.0150724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.97547e-05 -0.00523 3.99985 0.0265493 0.00109181 +EDGE_SE3:QUAT 471 699 -3.39324 -4.61991 -0.0353038 0.0014845 -7.22411e-05 -0.979093 0.203406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.01021e-05 0.00629011 4.00003 -0.00257526 0.165508 +EDGE_SE3:QUAT 585 699 3.73938 -4.33726 -0.0143171 -0.00426441 -0.00385679 0.944594 0.32819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.94966e-05 0.018494 3.99998 0.0214241 0.431049 +EDGE_SE3:QUAT 586 699 1.06512 -3.47296 -0.0576612 -0.00122161 -0.00737722 0.987137 0.1597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.44709e-05 0.00482925 3.99978 0.0291643 0.10224 +EDGE_SE3:QUAT 587 699 -1.80979 -3.54206 -0.0435878 -0.00236655 0.00596169 -0.999839 0.0167816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.36689e-05 -0.00947044 3.99994 0.0241478 0.00129474 +EDGE_SE3:QUAT 588 699 -4.81774 -4.34153 -0.134275 0.00959047 -0.00104802 -0.987439 0.157709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -0.000355917 0.0397343 4.00129 -0.0157414 0.0999544 +EDGE_SE3:QUAT 654 699 2.02662 -6.4784 -0.034804 -0.000144095 -0.000401838 0.849356 0.52782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.06517e-07 0.00028961 4 0.00104347 1.11437 +EDGE_SE3:QUAT 655 699 -1.99981 -6.38373 -0.06509 -0.000879154 -0.00180967 0.849476 0.527623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.52953e-06 0.00252404 3.99999 0.00540326 1.11356 +EDGE_SE3:QUAT 700 701 4.36098 0.534589 -0.0160512 -0.00835864 0.0128412 0.142336 0.9897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00295 0.000176492 0.113784 3.9992 0.00833796 3.92219 +EDGE_SE3:QUAT 467 700 3.39686 -2.4998 -0.0670497 0.0159042 -0.00230371 0.787934 0.61555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 0.00187348 -0.0924915 4.00105 -0.0469231 1.51869 +EDGE_SE3:QUAT 468 700 0.302307 -1.51158 -0.0197713 0.00119289 -0.0046867 0.919313 0.393497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.00652e-05 -0.00802932 4.00009 0.00872374 0.61941 +EDGE_SE3:QUAT 469 700 -2.89745 -2.25219 -0.0697118 -0.000573732 -0.0105756 0.991716 0.128015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.71601e-05 0.00217237 3.99958 0.0411551 0.0659835 +EDGE_SE3:QUAT 470 700 -5.32872 -4.50743 -0.0398964 -0.00253155 0.006692 -0.98906 0.147339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.88224e-05 -0.0102797 3.99983 0.028245 0.0870649 +EDGE_SE3:QUAT 516 700 3.69149 5.23334 0.00810273 0.00208951 -0.00187013 -0.438013 0.898964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.74766e-06 -0.001291 4 -0.000863766 3.23257 +EDGE_SE3:QUAT 517 700 -0.737002 5.33056 0.0211562 0.00875201 -0.00633901 -0.432431 0.901602 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 9.5879e-05 0.00258371 3.99998 -0.004943 3.25193 +EDGE_SE3:QUAT 584 700 3.49208 -2.45038 -0.0377922 0.00477262 -0.0051027 0.938589 0.344965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000179563 -0.0238582 4.00055 0.00299402 0.476172 +EDGE_SE3:QUAT 585 700 0.0159322 -1.89417 -0.0306109 -0.00294537 -0.00380728 0.979785 0.199997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.68316e-05 0.0122236 3.99998 0.018252 0.160119 +EDGE_SE3:QUAT 586 700 -3.27297 -2.44194 -0.046065 -0.000247604 -0.00780416 0.999592 0.0274818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.66883e-06 0.000990228 3.99976 0.0312112 0.00326497 +EDGE_SE3:QUAT 587 700 -6.24509 -4.07945 -0.0145567 -0.00340424 0.00581167 -0.988819 0.148966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.51483e-05 -0.0139096 3.99993 0.0259342 0.0889837 +EDGE_SE3:QUAT 653 700 3.79832 -2.75235 -0.0354971 0.00916902 0.002473 0.912788 0.408324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000467955 -0.0433041 4.00043 -0.0309838 0.667682 +EDGE_SE3:QUAT 654 700 -0.294418 -2.6637 -0.0226555 0.00142387 -0.0015642 0.911825 0.410573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.28041e-05 -0.00781023 4.00005 -0.000106799 0.674298 +EDGE_SE3:QUAT 655 700 -4.31274 -2.58122 -0.0601332 0.000325671 -0.00256282 0.911797 0.410633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.51579e-06 -0.00300795 4.00002 0.00530549 0.67449 +EDGE_SE3:QUAT 701 702 4.16749 0.415991 0.0206794 -0.000295328 -0.000591901 0.117458 0.993078 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.43285e-06 -0.00422512 4 -0.000238054 3.94482 +EDGE_SE3:QUAT 466 701 6.56892 -0.311372 0.0659877 -0.00148413 -0.00474663 0.734495 0.678596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.98226e-06 -0.00348985 4.00003 0.00544854 1.84203 +EDGE_SE3:QUAT 467 701 1.9805 1.53025 0.0452995 1.78705e-05 -0.00288613 0.867758 0.496978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.32253e-08 -0.00292675 4.00002 0.00501583 0.987964 +EDGE_SE3:QUAT 468 701 -2.99897 1.29425 0.0012659 -0.0140112 -0.00806172 0.966003 0.258023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000978311 0.0602734 4.00118 0.0540347 0.268011 +EDGE_SE3:QUAT 469 701 -7.13289 -1.56234 -0.0804747 0.0163228 0.0167609 -0.999613 0.0150205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99887 0.00103173 0.0653288 4.00334 0.0651342 0.0030294 +EDGE_SE3:QUAT 516 701 6.74362 2.11976 0.0129286 -0.000124312 0.0130814 -0.304817 0.952321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.002 -0.00104297 0.0900188 3.99978 -0.0129265 3.63035 +EDGE_SE3:QUAT 517 701 2.36611 2.25724 0.0383124 0.00547964 0.00761857 -0.299607 0.954016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00116 -0.000357842 0.0714711 3.99976 -0.0112469 3.64222 +EDGE_SE3:QUAT 518 701 -2.24829 2.36341 0.0271385 0.00403899 0.00301479 -0.289147 0.957272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -4.0599e-05 0.034393 3.99993 -0.00548935 3.66587 +EDGE_SE3:QUAT 519 701 -6.33443 2.36496 0.0411634 0.00239412 0.00476193 -0.279469 0.96014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -0.000129305 0.0413356 3.99992 -0.0059287 3.68801 +EDGE_SE3:QUAT 583 701 3.91323 -0.216982 0.0379802 -0.00538793 -0.00354503 0.964797 0.262918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000139745 0.0231543 4.00014 0.0223407 0.276773 +EDGE_SE3:QUAT 584 701 -0.106157 -0.00843962 0.0105032 -0.0107219 -0.00970902 0.978126 0.207511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000543192 0.0448861 4.0004 0.0517657 0.173453 +EDGE_SE3:QUAT 585 701 -4.08213 -0.600488 -0.0612016 -0.017944 -0.00851189 0.998122 0.0579511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 0.000993102 0.0721304 4.0044 0.0421237 0.0151824 +EDGE_SE3:QUAT 652 701 4.52153 0.0788888 0.0396141 -0.0055349 -0.000988807 0.96233 0.271825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000169886 0.0242966 4.00032 0.0143928 0.295765 +EDGE_SE3:QUAT 653 701 0.563929 0.149295 0.0247822 -0.00581294 -0.00132119 0.96174 0.2739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000186322 0.0255019 4.00033 0.0161043 0.300324 +EDGE_SE3:QUAT 654 701 -3.47229 0.259697 -0.0109579 -0.0140344 -0.00396458 0.960968 0.276274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.00107654 0.0615393 4.0018 0.0416003 0.306754 +EDGE_SE3:QUAT 702 703 4.34755 0.251774 0.0303998 -0.00220189 -0.00335283 0.0676705 0.9977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 4.29141e-05 -0.0248566 3.99996 -0.000819396 3.98184 +EDGE_SE3:QUAT 466 702 5.85525 3.78871 0.107689 -0.0019212 -0.00531306 0.809021 0.587753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -4.3164e-05 0.00188251 3.99998 0.0112272 1.38189 +EDGE_SE3:QUAT 467 702 -0.428247 4.90388 0.080719 -5.80154e-05 -0.00343509 0.920095 0.391681 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.39799e-05 -0.00137228 4 0.00891736 0.613684 +EDGE_SE3:QUAT 468 702 -6.74022 3.03118 -0.0755439 -0.0146027 -0.00726297 0.989645 0.142605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 0.000938264 0.0600108 4.00233 0.0439486 0.082749 +EDGE_SE3:QUAT 517 702 6.00308 0.207178 -0.0147477 0.00608157 0.00653437 -0.185281 0.982645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 -5.68395e-05 0.0628307 3.99976 -0.00614752 3.86367 +EDGE_SE3:QUAT 518 702 1.42894 0.382361 0.0189215 0.00381984 0.00214698 -0.174733 0.984606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.66438e-05 0.0242421 3.99996 -0.00232705 3.87802 +EDGE_SE3:QUAT 519 702 -2.60422 0.470464 0.0222358 0.0023043 0.00402963 -0.164935 0.986294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -3.35192e-05 0.0354109 3.99993 -0.00300818 3.8915 +EDGE_SE3:QUAT 520 702 -6.74875 0.479329 -0.00446233 0.0016424 0.00296928 -0.156499 0.987672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -1.6579e-05 0.0259219 3.99996 -0.00208543 3.9022 +EDGE_SE3:QUAT 582 702 4.49598 1.48254 0.0474706 -0.00604194 -0.00256064 0.988995 0.1478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000158103 0.0248813 4.00042 0.0166783 0.087608 +EDGE_SE3:QUAT 583 702 0.106785 1.54841 0.0277033 -0.00519295 -0.0036623 0.98899 0.147849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000127627 0.0213479 4.00023 0.0198648 0.0876536 +EDGE_SE3:QUAT 584 702 -4.04741 1.34305 -0.0370181 -0.0114323 -0.00924829 0.995805 0.0903102 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000588256 0.0462399 4.00127 0.0444579 0.0336592 +EDGE_SE3:QUAT 651 702 4.92625 1.83015 0.0466718 -0.00687591 -0.000731948 0.987861 0.155186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000180378 0.0284576 4.00067 0.0110869 0.0965684 +EDGE_SE3:QUAT 652 702 0.792298 1.9091 0.0205756 -0.00511291 -0.000833352 0.987538 0.157295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000103945 0.0211707 4.00035 0.00940513 0.099104 +EDGE_SE3:QUAT 653 702 -3.16592 2.01646 0.00641611 -0.00569889 -0.000977792 0.987284 0.158862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000130601 0.023611 4.00044 0.0107285 0.101121 +EDGE_SE3:QUAT 703 704 4.39168 0.107748 0.0162638 -0.00512092 -0.00211075 0.0383508 0.999249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.83166e-05 -0.0144939 3.99999 -0.000263064 3.99417 +EDGE_SE3:QUAT 518 703 5.59261 -0.882853 0.0330056 0.0010175 -0.00124242 -0.107795 0.994172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.18986e-06 -0.00846067 4 0.000429261 3.95354 +EDGE_SE3:QUAT 519 703 1.57923 -0.723836 0.0177098 -0.000286472 0.000946835 -0.0978508 0.995201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.92738e-06 0.00713194 4 -0.000341669 3.96171 +EDGE_SE3:QUAT 520 703 -2.54377 -0.639041 -0.00280635 -0.000741846 -0.000115416 -0.0893832 0.995997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.50319e-07 -0.00170375 4 8.783e-05 3.96804 +EDGE_SE3:QUAT 521 703 -6.64129 -0.629481 0.0124418 0.00175532 0.00228449 -0.0814705 0.996672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 6.2168e-06 0.0198031 3.99997 -0.000827302 3.97355 +EDGE_SE3:QUAT 581 703 4.58647 2.46754 0.0374403 -0.00282788 -0.00426573 0.997263 0.0737621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.76162e-05 0.0113901 4.00001 0.0184913 0.0218819 +EDGE_SE3:QUAT 582 703 0.259307 2.52424 0.0297956 -0.00323462 -0.00497616 0.996727 0.0806276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.22319e-05 0.0130437 4.00001 0.0216553 0.0261639 +EDGE_SE3:QUAT 583 703 -4.10901 2.60047 0.0112543 -0.00252922 -0.00587249 0.996732 0.08052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.39331e-05 0.0101907 3.99991 0.0247288 0.0261138 +EDGE_SE3:QUAT 650 703 4.87387 2.85154 0.0305251 -0.00309877 -0.00314336 0.996274 0.0861291 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.73731e-05 0.0125164 4.00007 0.0144607 0.0297649 +EDGE_SE3:QUAT 651 703 0.747092 2.93483 0.0171885 -0.00390152 -0.00278136 0.996087 0.088249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.45565e-05 0.0157723 4.00016 0.0136433 0.031261 +EDGE_SE3:QUAT 652 703 -3.40721 3.03573 0.0104045 -0.0021893 -0.00350583 0.995906 0.0903055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.84066e-05 0.00884318 4 0.0153072 0.032699 +EDGE_SE3:QUAT 704 705 4.05246 -0.0046246 0.0191945 0.00294658 -0.00171336 0.021059 0.999772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.00289e-05 -0.0144421 3.99999 -0.000154429 3.99828 +EDGE_SE3:QUAT 519 704 5.87702 -1.47434 0.025622 -0.00554701 -0.000826443 -0.0597967 0.998195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 3.08001e-05 -0.0105466 3.99999 0.000354447 3.98572 +EDGE_SE3:QUAT 520 704 1.77256 -1.31878 0.0101915 -0.00607299 -0.0017784 -0.0511471 0.998671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 5.24472e-05 -0.0178917 3.99998 0.000488202 3.98962 +EDGE_SE3:QUAT 521 704 -2.3239 -1.24244 0.00238272 -0.00341035 0.000443402 -0.0433911 0.999052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.06758e-06 0.00176364 4 -2.53542e-05 3.99247 +EDGE_SE3:QUAT 522 704 -6.40414 -1.18468 -0.0940957 -0.00251053 -0.00459311 -0.0377692 0.999273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 2.79044e-05 -0.0378057 3.99991 0.000719446 3.99465 +EDGE_SE3:QUAT 580 704 4.23014 2.92536 0.0510895 -0.00276747 -0.0102013 0.999398 0.0330585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.96162e-05 0.0110866 3.99966 0.041424 0.00483168 +EDGE_SE3:QUAT 581 704 0.259394 3.01499 0.0244556 -0.00128241 -0.00944416 0.999322 0.0355632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.36277e-05 0.00513642 3.99965 0.0380201 0.00542744 +EDGE_SE3:QUAT 582 704 -4.08426 3.14304 0.0173273 -0.00169137 -0.0102324 0.999053 0.0422485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.50286e-05 0.00677814 3.9996 0.0413157 0.00757879 +EDGE_SE3:QUAT 649 704 4.75835 3.41718 0.0326989 -0.00421124 -0.00713985 0.998884 0.0465046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000117061 0.0168951 4.00001 0.02997 0.00894719 +EDGE_SE3:QUAT 650 704 0.546556 3.5062 0.0188689 -0.00154823 -0.00825716 0.998813 0.0479766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.61018e-05 0.00620742 3.99974 0.0334306 0.00949673 +EDGE_SE3:QUAT 651 704 -3.60087 3.60688 0.0013861 -0.00224408 -0.00828114 0.998712 0.0500133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.02465e-05 0.00900242 3.99977 0.0338126 0.0103122 +EDGE_SE3:QUAT 705 706 4.56108 -0.00180844 -0.00352205 -0.00374656 0.0036351 0.0194161 0.999798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -5.01804e-05 0.0299379 3.99994 0.000292207 3.99872 +EDGE_SE3:QUAT 520 705 5.77745 -1.74805 0.0476874 -0.00331249 -0.00343939 -0.0299817 0.999539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 3.90472e-05 -0.02867 3.99995 0.000434608 3.99661 +EDGE_SE3:QUAT 521 705 1.72399 -1.5964 0.00720113 -0.000299698 -0.00127509 -0.0217376 0.999763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 6.85158e-07 -0.0102717 3.99999 0.000111888 3.99814 +EDGE_SE3:QUAT 522 705 -2.35438 -1.50571 -0.0434419 0.000409938 -0.00628979 -0.016429 0.999845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -2.58469e-05 -0.0502241 3.99984 0.000412847 3.99955 +EDGE_SE3:QUAT 523 705 -6.58331 -1.43337 -0.00777495 -0.00113104 -0.00241934 -0.0133278 0.999908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 9.17987e-06 -0.0195308 3.99998 0.000130388 3.99938 +EDGE_SE3:QUAT 579 705 4.58024 3.15227 0.0339847 0.00085876 -0.00532114 0.999958 0.00736593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.97994e-05 -0.00343549 3.9999 0.0212309 0.000332674 +EDGE_SE3:QUAT 580 705 0.184563 3.21183 0.043359 -0.00132375 -0.00696439 0.999906 0.0117571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.27274e-05 0.00529638 3.99983 0.027972 0.000755574 +EDGE_SE3:QUAT 581 705 -3.77962 3.33256 0.0318655 0.000160621 -0.00631966 0.99988 0.0141422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.55255e-06 -0.000642885 3.99984 0.0252473 0.000959501 +EDGE_SE3:QUAT 648 705 4.92474 3.72104 0.0206595 0.000535558 -0.00357794 0.999673 0.0253057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.99631e-06 -0.0021448 3.99996 0.0141804 0.00261297 +EDGE_SE3:QUAT 649 705 0.738886 3.80388 0.0202724 -0.00258631 -0.00416283 0.999664 0.0254478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.31842e-05 0.010355 4.00002 0.017151 0.00269077 +EDGE_SE3:QUAT 650 705 -3.46282 3.90633 0.0225626 -0.000126702 -0.00508636 0.999619 0.0271227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.0371e-06 0.000506548 3.9999 0.0203353 0.00304609 +EDGE_SE3:QUAT 706 707 4.3667 -0.00114374 0.0230295 -0.00182068 -0.00108686 0.0183264 0.99983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.90678e-06 -0.00829014 4 -7.47766e-05 3.99867 +EDGE_SE3:QUAT 521 706 6.26285 -1.80724 0.0206043 -0.00425264 0.00236183 -0.00230165 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.01495e-05 0.0187769 3.99998 -2.21287e-05 4.00007 +EDGE_SE3:QUAT 522 706 2.16968 -1.65993 0.00753753 -0.00332018 -0.00261184 0.00316442 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 3.49231e-05 -0.0207685 3.99997 -3.33341e-05 4.00007 +EDGE_SE3:QUAT 523 706 -2.05405 -1.55746 0.00749131 -0.00479891 0.00128506 0.00624868 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -2.55551e-05 0.0106394 3.99999 3.34149e-05 3.99987 +EDGE_SE3:QUAT 524 706 -6.26754 -1.47749 0.00539207 -0.00545569 0.00231452 0.00796845 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.13315e-05 0.0190356 3.99998 7.58034e-05 3.99984 +EDGE_SE3:QUAT 578 706 4.03493 3.12848 0.0785969 0.00554691 0.0129462 -0.999788 0.0150231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000295288 0.0222006 3.99987 0.0510943 0.00167881 +EDGE_SE3:QUAT 579 706 0.0477371 3.22153 0.0336007 0.00287389 0.00909241 -0.999881 0.0120875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000109868 0.0114996 3.99982 0.0360788 0.000942974 +EDGE_SE3:QUAT 580 706 -4.36013 3.32768 0.0297576 0.00525977 0.0110433 -0.999896 0.00764948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000234545 0.0210445 3.99998 0.0438492 0.000825478 +EDGE_SE3:QUAT 647 706 4.49284 3.85965 0.0458021 -0.00491417 -0.00800805 0.999935 0.00638691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000157765 0.0196596 4.00012 0.0322832 0.000520342 +EDGE_SE3:QUAT 648 706 0.414341 3.95368 0.0273563 -0.00338971 -0.00763946 0.999948 0.00584547 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000102412 0.0135606 3.99994 0.0307147 0.000418507 +EDGE_SE3:QUAT 649 706 -3.77481 4.04302 -0.00690771 -0.00654957 -0.00790221 0.999927 0.00629932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000210327 0.0262018 4.00042 0.0319422 0.00058541 +EDGE_SE3:QUAT 707 708 4.38008 -0.0491337 0.0238853 0.00226887 -0.000935524 0.0113772 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.7021e-06 -0.00779244 4 -4.48624e-05 3.9995 +EDGE_SE3:QUAT 522 707 6.53052 -1.63973 0.0538345 -0.00519134 -0.00352964 0.0213694 0.999752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 7.45527e-05 -0.0268869 3.99996 -0.000283938 3.99835 +EDGE_SE3:QUAT 523 707 2.3191 -1.50627 0.0207731 -0.00667592 0.000265733 0.0242916 0.999683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -1.56252e-05 0.00406905 4 5.72595e-05 3.99764 +EDGE_SE3:QUAT 524 707 -1.89091 -1.40716 0.0031913 -0.00683556 0.00124863 0.0259363 0.999639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -4.24674e-05 0.0121048 3.99999 0.000165783 3.99735 +EDGE_SE3:QUAT 525 707 -6.02726 -1.30264 -0.024883 -0.00720496 0.000888591 0.025621 0.999645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -3.54618e-05 0.00931536 3.99999 0.000128552 3.9974 +EDGE_SE3:QUAT 577 707 3.69332 2.91024 0.07436 0.00596075 0.0148414 -0.999259 0.0350094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000378581 0.0238989 3.99984 0.0575238 0.0058739 +EDGE_SE3:QUAT 578 707 -0.333918 2.99205 0.0512134 0.00475065 0.0145273 -0.999326 0.0333614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000309164 0.0190444 3.99963 0.056684 0.00534694 +EDGE_SE3:QUAT 579 707 -4.3439 3.12123 0.0341582 0.00204913 0.0111123 -0.999488 0.0299412 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000116209 0.00821162 3.99961 0.0438581 0.00408415 +EDGE_SE3:QUAT 646 707 4.30925 3.7927 0.0523087 0.00604549 0.0102407 -0.999899 0.00782814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.00024718 0.0241875 4.00019 0.0405844 0.000803142 +EDGE_SE3:QUAT 647 707 0.146843 3.90949 0.031118 0.0041251 0.0100956 -0.999876 0.011383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000170875 0.0165061 3.99989 0.0399958 0.00098638 +EDGE_SE3:QUAT 648 707 -3.95878 4.01247 0.0259207 0.00260454 0.00965074 -0.999875 0.0122166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000107403 0.0104221 3.99975 0.0383338 0.000991584 +EDGE_SE3:QUAT 708 709 4.15341 -0.0534928 0.0221885 -3.44503e-05 -0.00548421 0.0107707 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 8.5287e-06 -0.0438662 3.99988 -0.000236312 4.00002 +EDGE_SE3:QUAT 523 708 6.66201 -1.34391 0.042877 -0.00443989 -0.00030504 0.0359092 0.999345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -2.44484e-07 -0.000524002 4 2.06923e-06 3.99484 +EDGE_SE3:QUAT 524 708 2.47288 -1.22894 0.0132602 -0.00455293 0.000558499 0.0373112 0.999293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -1.58147e-05 0.00649513 4 0.000133726 3.99444 +EDGE_SE3:QUAT 525 708 -1.65069 -1.1293 -0.0100462 -0.00463378 0.000251265 0.0367836 0.999312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -1.07808e-05 0.00404947 4 8.69685e-05 3.99459 +EDGE_SE3:QUAT 526 708 -6.13941 -1.02771 -0.0863998 -0.000869779 -0.00259227 0.0343285 0.999407 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.41677e-05 -0.0203439 3.99997 -0.000347088 3.99539 +EDGE_SE3:QUAT 576 708 3.9367 2.42253 0.0600353 0.00439402 0.0137902 -0.999714 0.019012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000261038 0.0175912 3.99961 0.0544443 0.00226458 +EDGE_SE3:QUAT 577 708 -0.640315 2.65159 0.0426395 0.00552618 0.0124239 -0.998831 0.0463845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000288138 0.02219 4.00003 0.0473888 0.00929216 +EDGE_SE3:QUAT 578 708 -4.67543 2.75343 0.0333871 0.0044258 0.0123999 -0.998916 0.0446383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000246066 0.0177686 3.99982 0.0477785 0.00862131 +EDGE_SE3:QUAT 645 708 4.04846 3.65408 0.0400779 0.0047238 0.00809743 -0.999872 0.0129492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000152479 0.0189016 4.00012 0.03189 0.00101433 +EDGE_SE3:QUAT 646 708 -0.00857788 3.7784 0.0216476 0.00544115 0.00751358 -0.999773 0.0191607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000157659 0.0217783 4.00029 0.0291972 0.00180033 +EDGE_SE3:QUAT 647 708 -4.22167 3.85967 0.0152918 0.00358566 0.007445 -0.999709 0.0226612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000108954 0.0143554 4.00001 0.0290936 0.00231739 +EDGE_SE3:QUAT 709 710 4.24662 -0.0393599 -0.00381558 0.00197369 0.0164561 0.0113557 0.999798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0043 0.000203666 0.131477 3.99892 0.000760866 4.0038 +EDGE_SE3:QUAT 524 709 6.62756 -0.976027 0.0401784 -0.0046669 -0.00454344 0.0481571 0.998819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 9.7146e-05 -0.0335291 3.99993 -0.000786864 3.991 +EDGE_SE3:QUAT 525 709 2.49117 -0.880777 0.00569502 -0.00445205 -0.00513676 0.0475701 0.998845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 0.000110732 -0.0384188 3.99991 -0.000895305 3.99132 +EDGE_SE3:QUAT 526 709 -1.98882 -0.801295 -0.0409234 -0.000568431 -0.00790757 0.045056 0.998953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00098 8.46813e-05 -0.0627745 3.99976 -0.00141219 3.99286 +EDGE_SE3:QUAT 527 709 -6.2662 -0.671257 -0.107693 -0.00104129 -0.0143627 0.0418598 0.99902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00325 0.000264736 -0.114158 3.9992 -0.0023938 3.99625 +EDGE_SE3:QUAT 575 709 4.42226 1.74041 0.0373839 0.00261814 -0.0130889 0.997242 0.0730057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000211207 -0.0105999 3.99957 0.050138 0.0219797 +EDGE_SE3:QUAT 576 709 -0.214256 2.31397 0.0510997 -0.00090323 0.0136985 -0.999455 0.0300172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.47216e-06 -0.00361524 3.99925 0.0548821 0.00436124 +EDGE_SE3:QUAT 577 709 -4.73029 2.33251 0.0239589 0.000704389 0.0124202 -0.998257 0.0576874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000102568 0.0028521 3.99943 0.0489408 0.0139143 +EDGE_SE3:QUAT 644 709 3.88034 3.48691 0.0514552 -0.00049736 0.0102347 -0.999819 0.0160114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.9673e-06 -0.00199004 3.99958 0.0409742 0.00144632 +EDGE_SE3:QUAT 645 709 -0.131066 3.60349 0.0245584 -0.000423134 0.00779175 -0.999695 0.0234216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.82383e-06 -0.00169319 3.99976 0.0312025 0.00243855 +EDGE_SE3:QUAT 646 709 -4.13636 3.67223 -0.000375087 0.000527312 0.00718685 -0.99953 0.0298114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.70123e-05 0.00211383 3.9998 0.0285573 0.00376008 +EDGE_SE3:QUAT 710 711 4.25063 0.00316565 0.0189771 0.000524743 -0.00372694 0.0196826 0.999799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -1.26187e-06 -0.0299235 3.99994 -0.000294704 3.99867 +EDGE_SE3:QUAT 525 710 6.694 -0.530287 0.048989 -0.00317839 0.0116234 0.0589963 0.998185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0022 4.56471e-05 0.0947929 3.99944 0.00280698 3.98832 +EDGE_SE3:QUAT 526 710 2.23049 -0.458703 0.0185036 0.000687923 0.00860706 0.0565332 0.998363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00116 0.000122249 0.068078 3.99972 0.0019195 3.98837 +EDGE_SE3:QUAT 527 710 -2.01933 -0.367836 0.00571413 0.000301848 0.00220745 0.0531444 0.998584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 8.6902e-06 0.017393 3.99998 0.000459858 3.98878 +EDGE_SE3:QUAT 528 710 -6.30456 -0.199583 0.0137192 -0.00096694 0.00397328 0.0447411 0.99899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 1.67938e-06 0.0322111 3.99994 0.000723486 3.99225 +EDGE_SE3:QUAT 574 710 4.96244 1.52711 0.0784121 -0.00622919 -0.0112454 0.977922 0.208575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000102065 0.0256765 3.99956 0.0501046 0.174835 +EDGE_SE3:QUAT 575 710 0.209259 2.42374 0.0627352 -0.0138495 -0.00947582 0.997937 0.0619613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 0.00073354 0.055707 4.0023 0.0444195 0.0166298 +EDGE_SE3:QUAT 576 710 -4.38723 2.10933 0.0593425 0.0158865 0.0120005 -0.998941 0.0414718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 0.000541148 0.0637149 4.00383 0.042593 0.00835047 +EDGE_SE3:QUAT 643 710 3.6322 3.35771 0.0636739 0.00807849 0.00642445 -0.99925 0.0373315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000157081 0.0323842 4.00097 0.0232073 0.00597197 +EDGE_SE3:QUAT 644 710 -0.281754 3.39193 0.0529765 0.0163377 0.00835496 -0.999458 0.0273143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 0.000381807 0.0654197 4.00417 0.029833 0.0042777 +EDGE_SE3:QUAT 645 710 -4.27021 3.45084 0.0285099 0.0164622 0.00602219 -0.99923 0.0351094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99887 0.000172277 0.0659641 4.00435 0.019424 0.00611451 +EDGE_SE3:QUAT 711 712 4.2064 0.00802182 0.0190911 0.00256177 -0.00158569 0.0224098 0.999744 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.59414e-05 -0.0133646 3.99999 -0.000152123 3.99804 +EDGE_SE3:QUAT 526 711 6.47235 -0.00191322 -0.0336276 0.00159733 0.00496172 0.0759343 0.997099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 7.16904e-05 0.0379038 3.99992 0.00141755 3.97729 +EDGE_SE3:QUAT 527 711 2.20927 0.077661 0.00491881 0.00112501 -0.00153691 0.0725582 0.997362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.98046e-06 -0.0131745 3.99999 -0.000488567 3.97898 +EDGE_SE3:QUAT 528 711 -2.07693 0.17393 -0.00360544 -0.000178727 0.000112911 0.0645282 0.997916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.19534e-08 0.00103566 4 3.48422e-05 3.98334 +EDGE_SE3:QUAT 529 711 -6.36537 0.450274 -0.000544696 0.00040022 0.0019807 0.044612 0.999002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 7.19886e-06 0.0155846 3.99999 0.000345734 3.9921 +EDGE_SE3:QUAT 573 711 5.97703 2.1783 0.0644783 -0.000810519 -0.0115235 0.941778 0.336038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.00020265 0.000243484 3.99978 0.0355416 0.452062 +EDGE_SE3:QUAT 574 711 1.07378 3.29065 0.0667555 -0.00263649 -0.0115144 0.981765 0.189731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.55585e-05 0.0104704 3.99946 0.0458194 0.144564 +EDGE_SE3:QUAT 575 711 -3.97573 2.94764 -0.0281352 -0.010305 -0.00908044 0.999008 0.0423604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000443903 0.0413306 4.00118 0.0396645 0.00799917 +EDGE_SE3:QUAT 642 711 3.4132 2.99421 0.0419979 0.00364207 0.00667566 -0.997655 0.068023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.23799e-05 0.0146864 4.00012 0.0244233 0.0187126 +EDGE_SE3:QUAT 643 711 -0.596925 3.06352 0.0170465 0.00478541 0.00581091 -0.998377 0.0564479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.97999e-05 0.0192416 4.00031 0.0209072 0.012948 +EDGE_SE3:QUAT 644 711 -4.38927 3.16566 -0.0672367 0.0129777 0.0071898 -0.998766 0.0473957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99927 0.000189225 0.0520881 4.00269 0.0237096 0.00980623 +EDGE_SE3:QUAT 712 713 4.2033 0.00363236 0.0173042 0.000153334 -0.00143294 0.0257732 0.999667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.94165e-07 -0.0114996 3.99999 -0.000148341 3.99738 +EDGE_SE3:QUAT 527 712 6.35352 0.672797 0.0401341 0.0033246 -0.00275657 0.0949805 0.99547 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.24418e-05 -0.0255219 3.99996 -0.00126661 3.96408 +EDGE_SE3:QUAT 528 712 2.06745 0.707071 0.011355 0.00257546 -0.00131344 0.0867388 0.996227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.28202e-05 -0.0130564 3.99999 -0.000603138 3.96995 +EDGE_SE3:QUAT 529 712 -2.1786 0.811718 -0.00135646 0.00293162 0.000448714 0.066877 0.997757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.0166e-07 0.00121994 4 1.43032e-05 3.98211 +EDGE_SE3:QUAT 530 712 -6.29235 1.16412 0.0394959 0.00322908 0.00458549 0.0413698 0.999128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 7.50112e-05 0.0349902 3.99993 0.00071373 3.99346 +EDGE_SE3:QUAT 573 712 2.7444 4.83121 0.107319 0.00152704 -0.00958748 0.949107 0.314803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -9.30547e-05 -0.00933945 4.0001 0.0257228 0.396629 +EDGE_SE3:QUAT 574 712 -2.81702 4.87 0.0875487 -0.00081456 -0.00950249 0.985736 0.16803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.62345e-05 0.00303196 3.99967 0.0364162 0.113281 +EDGE_SE3:QUAT 641 712 3.2465 2.32766 0.0244135 0.00397141 0.00246658 -0.995699 0.0925315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 3.72136e-06 0.0161038 4.00027 0.00674164 0.0343253 +EDGE_SE3:QUAT 642 712 -0.739735 2.44498 0.0281161 0.00208338 0.00401078 -0.995905 0.0902965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.10309e-05 0.00845855 4.00004 0.0142247 0.032683 +EDGE_SE3:QUAT 643 712 -4.72599 2.61386 -0.00941335 0.00334071 0.00300916 -0.996885 0.0787437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 2.09459e-05 0.0134983 4.00018 0.00975965 0.0248721 +EDGE_SE3:QUAT 713 714 4.19675 0.0806382 0.0152053 0.00044276 -0.00117794 0.055729 0.998445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.23771e-07 -0.00967515 3.99999 -0.000271923 3.9876 +EDGE_SE3:QUAT 528 713 6.20444 1.42697 0.0440399 0.00260226 -0.00294621 0.11237 0.993659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -7.42736e-06 -0.0266049 3.99995 -0.00155156 3.94967 +EDGE_SE3:QUAT 529 713 1.97366 1.36951 0.0185286 0.00285192 -0.00114995 0.0923551 0.995721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.42377e-05 -0.0122249 3.99999 -0.000611206 3.96592 +EDGE_SE3:QUAT 530 713 -2.0976 1.50052 0.0178331 0.00348851 0.00323378 0.0667026 0.997762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 5.21703e-05 0.0229139 3.99997 0.000732035 3.98233 +EDGE_SE3:QUAT 531 713 -5.95531 2.37367 -0.0580572 -0.000948247 -0.00166928 -0.0200419 0.999797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 5.09568e-06 -0.0135743 3.99999 0.000136701 3.99844 +EDGE_SE3:QUAT 573 713 -0.609547 7.33523 0.16241 0.00286462 -0.00993047 0.956888 0.290275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -7.01032e-05 -0.0147553 4.00029 0.0255175 0.337291 +EDGE_SE3:QUAT 640 713 3.74108 1.17785 0.0237001 0.00326236 0.00654126 -0.998914 0.0460066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.63776e-05 0.0130965 4.00005 0.0248298 0.00866388 +EDGE_SE3:QUAT 641 713 -0.880923 1.57462 0.0118242 0.00248025 0.00219451 -0.992992 0.118139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.24928e-06 0.0101554 4.00011 0.00616206 0.0558634 +EDGE_SE3:QUAT 642 713 -4.87422 1.69313 0.0243771 0.000621679 0.00362434 -0.993277 0.115699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.74914e-05 0.00258112 3.99997 0.0134468 0.0535931 +EDGE_SE3:QUAT 714 715 4.11628 0.334361 0.00729217 0.00246081 0.00424003 0.124192 0.992246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 7.80794e-05 0.0295098 3.99995 0.00174127 3.93852 +EDGE_SE3:QUAT 529 714 6.10074 2.2148 0.0480849 0.0032769 -0.00228347 0.147833 0.989004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -1.33947e-05 -0.0234012 3.99996 -0.00185744 3.91272 +EDGE_SE3:QUAT 530 714 2.05743 2.1426 0.0114225 0.00423866 0.00175693 0.122217 0.992493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.5189e-05 0.00758684 4 0.000330652 3.94026 +EDGE_SE3:QUAT 531 714 -1.73948 2.28433 -0.0246328 -0.000675627 -0.00313919 0.0358275 0.999353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 1.66347e-05 -0.0247757 3.99996 -0.000442005 3.99502 +EDGE_SE3:QUAT 532 714 -5.22098 3.35603 0.0120168 0.00364259 -0.000950256 -0.0987833 0.995102 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -3.78021e-06 -0.0032011 4 8.51976e-05 3.96097 +EDGE_SE3:QUAT 639 714 3.782 0.157097 0.00812501 -0.00098092 -0.0065326 0.999547 0.0293713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.59653e-05 0.00392762 3.99984 0.0263039 0.00362768 +EDGE_SE3:QUAT 640 714 -0.44826 0.713494 0.0145405 0.00253168 0.00591204 -0.994787 0.10177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.18356e-05 0.010333 4.00004 0.0209991 0.0415674 +EDGE_SE3:QUAT 641 714 -4.94607 0.505791 0.00888486 0.00150826 0.00163489 -0.984892 0.173156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.55522e-07 0.00636611 4.00004 0.00402795 0.119947 +EDGE_SE3:QUAT 715 716 4.11497 0.564069 0.0165128 -0.000406627 -0.00660675 0.160815 0.986962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 0.000166802 -0.0500524 3.99987 -0.00394972 3.89718 +EDGE_SE3:QUAT 530 715 5.96205 3.4595 0.0113077 0.00620594 0.00581547 0.244404 0.969636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000136094 0.0249392 4 0.00213262 3.76121 +EDGE_SE3:QUAT 531 715 2.32785 2.91171 0.00318953 0.00134195 0.00134228 0.159537 0.98719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.88688e-06 0.00780542 4 0.000543273 3.89821 +EDGE_SE3:QUAT 532 715 -1.12201 2.85824 0.0223416 0.00652439 0.00247036 0.0255154 0.99965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 5.88669e-05 0.0177458 3.99998 0.000218636 3.99747 +EDGE_SE3:QUAT 533 715 -4.24864 3.9033 -0.000597517 0.00235986 0.00384287 -0.132915 0.991117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -1.3929e-05 0.0336534 3.99993 -0.00230103 3.92962 +EDGE_SE3:QUAT 638 715 3.96649 -0.692149 0.0142899 -0.00549569 -0.00487362 0.995748 0.0918224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000141578 0.02223 4.00027 0.0230906 0.033984 +EDGE_SE3:QUAT 639 715 -0.344547 0.0659087 0.00349259 0.00598606 0.00375871 -0.995444 0.0950851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 7.02475e-06 0.024292 4.00061 0.0101857 0.03634 +EDGE_SE3:QUAT 640 715 -4.40211 -0.433394 -0.00975977 0.00763279 0.00365406 -0.974485 0.224294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 -0.000240199 0.0330756 4.00104 -0.000197877 0.201519 +EDGE_SE3:QUAT 716 717 4.15662 0.523016 0.00472962 0.000313376 -0.00199299 0.146938 0.989144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.16984e-05 -0.0159752 3.99999 -0.00117438 3.9137 +EDGE_SE3:QUAT 532 716 2.95147 3.61529 0.024498 0.00658097 -0.00524012 0.185675 0.982575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 -4.32621e-06 -0.0541048 3.99981 -0.00540296 3.86283 +EDGE_SE3:QUAT 533 716 -0.132585 3.34631 -0.0147214 0.00156875 -0.00282441 0.0282574 0.999595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -1.2651e-05 -0.0231005 3.99997 -0.000328474 3.99694 +EDGE_SE3:QUAT 534 716 -3.17762 4.04425 -0.0315322 -0.000658342 -0.00169297 -0.148015 0.988983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -6.38247e-06 -0.0142535 3.99999 0.00107253 3.91242 +EDGE_SE3:QUAT 637 716 3.95176 -1.2369 -0.013004 -0.00133038 -0.00652485 0.993212 0.116127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.02481e-06 0.00534641 3.99983 0.0264423 0.0541266 +EDGE_SE3:QUAT 638 716 -0.183372 -0.468913 -0.0139002 -0.000239786 0.00522596 -0.997533 0.0699987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.02401e-05 -0.000951788 3.99989 0.0207816 0.019708 +EDGE_SE3:QUAT 639 716 -4.28148 -1.2445 -0.0289341 6.24146e-05 0.00305246 -0.967181 0.254071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.35923e-05 0.000673175 3.99998 0.0101659 0.258238 +EDGE_SE3:QUAT 717 718 4.33205 0.452308 -0.0303778 -0.00175325 0.0173542 0.110223 0.993754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0048 0.000678776 0.138758 3.99886 0.0076546 3.95621 +EDGE_SE3:QUAT 533 717 3.9893 4.09579 0.0142761 0.0014442 -0.00512461 0.174747 0.984599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 8.59313e-05 -0.0421043 3.9999 -0.00371113 3.8783 +EDGE_SE3:QUAT 534 717 0.944407 3.34531 -0.0163274 -0.000932735 -0.00378557 -0.00140247 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 1.36535e-05 -0.0303017 3.99994 2.09344e-05 4.00022 +EDGE_SE3:QUAT 535 717 -2.50947 3.57932 -0.0670387 0.00259552 -0.0132728 -0.140681 0.989963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00241 -0.000662134 -0.0987708 3.99947 0.00679177 3.92327 +EDGE_SE3:QUAT 636 717 3.65986 -1.34026 -0.0261234 0.00302965 -0.0070133 0.991594 0.129166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -8.21475e-05 -0.0125393 4.0001 0.0238131 0.0669207 +EDGE_SE3:QUAT 637 717 -0.233695 -0.78342 -0.0209599 1.83493e-05 0.00627885 -0.999492 0.031247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.02649e-05 7.51029e-05 3.99984 0.025049 0.00406252 +EDGE_SE3:QUAT 638 717 -4.2288 -1.55847 -0.0141382 -0.00161915 0.0049029 -0.976513 0.215394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.12525e-05 -0.00651949 3.9999 0.0200345 0.185695 +EDGE_SE3:QUAT 718 719 4.05849 0.187185 0.0343405 -0.00538166 0.000599241 0.061076 0.998118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.55233e-05 0.00870137 3.99999 0.000305475 3.9851 +EDGE_SE3:QUAT 534 718 5.28415 3.77291 -0.0167389 -0.00325796 0.0134311 0.108304 0.994022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00297 0.000307542 0.109837 3.99927 0.00598693 3.95609 +EDGE_SE3:QUAT 535 718 1.79044 2.78527 0.0132202 0.00187999 0.00381688 -0.0306205 0.999522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 1.84521e-05 0.031184 3.99994 -0.000480136 3.99649 +EDGE_SE3:QUAT 536 718 -2.49842 2.83994 0.0678968 0.00946542 0.00631626 -0.090006 0.995876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00054 0.000185815 0.0600912 3.99976 -0.00283771 3.9685 +EDGE_SE3:QUAT 537 718 -6.5126 3.01804 0.108084 0.00982693 0.00832866 -0.101453 0.994757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00111 0.000183406 0.0775025 3.9996 -0.00409864 3.96033 +EDGE_SE3:QUAT 635 718 3.26273 -0.815754 0.0171298 -0.00856519 -0.00534901 0.996094 0.0877149 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000293923 0.0346274 4.00085 0.026959 0.0312602 +EDGE_SE3:QUAT 636 718 -0.648601 -0.645246 -0.029146 -0.0149563 -0.00708143 0.999674 0.0194282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99914 0.000518874 0.0598586 4.00328 0.0306594 0.00264088 +EDGE_SE3:QUAT 637 718 -4.51659 -1.47416 -0.062964 0.0179497 0.00875674 -0.989859 0.140642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99857 -0.000534722 0.0740733 4.00562 0.0135256 0.0805702 +EDGE_SE3:QUAT 719 720 4.23562 0.0748247 0.0341243 -0.0043322 -0.00316224 0.0299272 0.999538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 5.67132e-05 -0.0237091 3.99997 -0.000347816 3.99656 +EDGE_SE3:QUAT 535 719 5.84737 2.72408 0.0165151 -0.003205 0.00433211 0.0302021 0.999529 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -4.36326e-05 0.0357724 3.99992 0.000544399 3.99667 +EDGE_SE3:QUAT 536 719 1.53535 2.28244 0.0429779 0.00449896 0.0068862 -0.0288332 0.99955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 9.42391e-05 0.0565851 3.9998 -0.000817985 3.99747 +EDGE_SE3:QUAT 537 719 -2.50592 2.37658 0.0671707 0.00502307 0.00873937 -0.0404441 0.999131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0012 0.000105364 0.072197 3.99967 -0.00146676 3.99476 +EDGE_SE3:QUAT 538 719 -6.6511 2.47599 -0.0175213 0.00702392 0.000807482 -0.0440038 0.999006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 3.85136e-05 0.0101447 3.99999 -0.000250037 3.99228 +EDGE_SE3:QUAT 634 719 3.55308 -0.332214 0.0245249 -0.00902399 -0.00414089 0.999514 0.0295414 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000201166 0.0361424 4.00118 0.0186663 0.00390477 +EDGE_SE3:QUAT 635 719 -0.751533 -0.291925 -0.0196174 -0.00983611 -0.0101413 0.999529 0.0272458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000435518 0.0393922 4.00101 0.0426512 0.00381247 +EDGE_SE3:QUAT 636 719 -4.69581 -0.666089 -0.124489 0.0162545 0.011418 -0.99895 0.041286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99883 0.000506455 0.0651874 4.00406 0.040176 0.00828643 +EDGE_SE3:QUAT 720 721 4.25833 -0.0331896 -0.00144112 -0.00175917 -0.000425754 0.00871595 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.81444e-06 -0.00322164 4 -1.3779e-05 3.9997 +EDGE_SE3:QUAT 536 720 5.76415 2.10401 0.0118597 0.000161431 0.00349786 0.00139039 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 2.66698e-06 0.0279813 3.99995 1.95017e-05 4.00019 +EDGE_SE3:QUAT 537 720 1.71482 2.09704 0.020595 0.000459184 0.00531259 -0.0107762 0.999928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 2.46287e-06 0.0425569 3.99989 -0.00022915 3.99999 +EDGE_SE3:QUAT 538 720 -2.43566 2.17244 0.00167836 0.00245128 -0.00244244 -0.0140052 0.999896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -2.52067e-05 -0.0191221 3.99998 0.000133276 3.99931 +EDGE_SE3:QUAT 539 720 -6.67537 2.2648 0.0782361 0.00253035 0.00545086 -0.0143193 0.999879 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 4.55365e-05 0.0440325 3.99988 -0.00031453 3.99966 +EDGE_SE3:QUAT 633 720 3.34374 -0.22659 -0.00852343 -0.000800762 0.00621879 -0.999962 0.00609142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.81153e-05 -0.00320339 3.99985 0.0249115 0.000306144 +EDGE_SE3:QUAT 634 720 -0.682489 -0.142235 -0.0250202 0.00565528 0.00847313 -0.999948 0.000554241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000191622 0.0226232 4.00023 0.0338722 0.000415981 +EDGE_SE3:QUAT 635 720 -4.97969 -0.123973 -0.0698187 0.0072255 0.0146979 -0.999861 0.00303762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000426315 0.0289109 3.99999 0.0586255 0.00110504 +EDGE_SE3:QUAT 721 722 4.28309 -0.0609426 0.0342827 -0.00111002 -0.00874518 0.00553798 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 4.89649e-05 -0.0699029 3.9997 -0.000195679 4.0011 +EDGE_SE3:QUAT 537 721 5.95652 1.97279 -0.0281195 -0.00109118 0.00506482 -0.00213139 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -2.34048e-05 0.0404939 3.9999 -4.38269e-05 4.00039 +EDGE_SE3:QUAT 538 721 1.80656 2.01995 0.017883 0.00089219 -0.00289624 -0.00529873 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.13655e-05 -0.0231128 3.99997 6.13676e-05 4.00002 +EDGE_SE3:QUAT 539 721 -2.4857 2.11138 0.0296716 0.000987258 0.00513993 -0.00544298 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 1.68867e-05 0.0411859 3.99989 -0.000111547 4.00031 +EDGE_SE3:QUAT 540 721 -6.72354 2.19204 0.0128132 -0.000916391 0.00676852 -0.00426846 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 -2.94845e-05 0.0541084 3.99982 -0.000116507 4.00066 +EDGE_SE3:QUAT 632 721 3.27044 -0.326209 0.0164879 0.00690067 0.00635575 -0.999786 0.0184282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000159488 0.0276178 4.00064 0.0243905 0.00169789 +EDGE_SE3:QUAT 633 721 -0.840611 -0.248695 -0.00355801 -0.00114534 0.0079056 -0.999863 0.0144772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.93171e-05 -0.00458299 3.99977 0.0317376 0.00109549 +EDGE_SE3:QUAT 634 721 -4.8724 -0.120756 -0.0782367 0.00547202 0.0101616 -0.99989 0.00929185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000223161 0.0218939 4.00009 0.0402359 0.000869939 +EDGE_SE3:QUAT 722 723 4.22188 -0.0777388 0.0249667 0.0029546 0.00496583 0.0047046 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 6.11423e-05 0.0395614 3.9999 9.46892e-05 4.0003 +EDGE_SE3:QUAT 538 722 6.07403 1.909 0.0726449 -0.000190542 -0.0115777 0.000573198 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00215 1.06857e-05 -0.0926633 3.99946 -2.72078e-05 4.00214 +EDGE_SE3:QUAT 539 722 1.81243 1.99695 0.0161233 9.5301e-05 -0.00358406 0.000191077 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -1.30761e-06 -0.028674 3.99995 -2.71047e-06 4.00021 +EDGE_SE3:QUAT 540 722 -2.3992 2.08695 -0.00985553 -0.00199801 -0.00178372 0.000673099 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.42859e-05 -0.0142537 3.99999 -4.94772e-06 4.00005 +EDGE_SE3:QUAT 541 722 -6.64933 2.17002 0.0441612 -0.00350438 0.00254244 0.00309498 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -3.54596e-05 0.0204695 3.99997 3.11962e-05 4.00007 +EDGE_SE3:QUAT 631 722 3.31927 -0.504586 0.0109256 0.00786494 0.00574632 -0.999567 0.0277508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000144863 0.0314971 4.00092 0.0212034 0.00344111 +EDGE_SE3:QUAT 632 722 -0.998584 -0.422119 -0.00789206 -0.00195759 0.00706485 -0.99968 0.0242006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.73845e-05 -0.00783698 3.99985 0.0285966 0.00256261 +EDGE_SE3:QUAT 633 722 -5.18445 -0.3012 0.0420605 -0.00963711 0.00887713 -0.999708 0.0203224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 -0.000372786 -0.0385754 4.00109 0.0370547 0.00236743 +EDGE_SE3:QUAT 723 724 4.12159 -0.0816414 0.043888 0.00283563 -0.00139272 0.00461528 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.58737e-05 -0.0112984 3.99999 -2.60587e-05 3.99995 +EDGE_SE3:QUAT 539 723 6.03571 1.92371 0.0708335 0.00316652 0.00141024 0.00461314 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.77064e-05 0.0111062 3.99999 2.563e-05 3.99995 +EDGE_SE3:QUAT 540 723 1.69989 2.03007 0.0291242 0.00109536 0.00317472 0.00561806 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 1.52098e-05 0.0253236 3.99996 7.13356e-05 4.00003 +EDGE_SE3:QUAT 541 723 -2.4398 2.11843 0.0471362 -0.000271311 0.0076116 0.00752139 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00093 2.19605e-06 0.0609245 3.99977 0.000228905 4.0007 +EDGE_SE3:QUAT 542 723 -6.67878 2.16675 0.0511104 -0.000569812 0.00628945 0.0116488 0.999912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -3.28386e-06 0.050392 3.99984 0.000293218 4.00009 +EDGE_SE3:QUAT 630 723 3.51683 -0.767283 0.0205505 0.0109418 0.00615316 -0.999272 0.0360349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 0.000171681 0.0438529 4.00187 0.0213964 0.00579008 +EDGE_SE3:QUAT 631 723 -0.87646 -0.664547 -0.030371 0.0130129 0.00263876 -0.999389 0.0323469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99931 5.86265e-06 0.0521294 4.00273 0.00716945 0.00487834 +EDGE_SE3:QUAT 632 723 -5.16437 -0.537986 0.0326635 0.0033526 0.00415636 -0.999568 0.028891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.11986e-05 0.0134282 4.00013 0.0158174 0.00344647 +EDGE_SE3:QUAT 724 725 4.42163 -0.0707044 0.0361517 0.0015677 -0.003505 0.00469211 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -2.06839e-05 -0.0281285 3.99995 -6.56032e-05 4.00011 +EDGE_SE3:QUAT 540 724 5.80572 1.99029 0.0452305 0.00388449 0.00190704 0.0102565 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.92397e-05 0.0147757 3.99999 7.52771e-05 3.99963 +EDGE_SE3:QUAT 541 724 1.63189 2.09942 0.0281134 0.00264092 0.00636902 0.0120331 0.999904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 7.82037e-05 0.0505663 3.99984 0.000306116 4.00006 +EDGE_SE3:QUAT 542 724 -2.56918 2.17921 0.0460909 0.00226384 0.00515671 0.016102 0.999854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 5.61318e-05 0.0408037 3.9999 0.000328804 3.99938 +EDGE_SE3:QUAT 543 724 -6.67324 2.22184 -0.186809 -0.00173581 -0.0103954 0.0211185 0.999721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0017 0.000126016 -0.0826979 3.99958 -0.00087693 3.99993 +EDGE_SE3:QUAT 629 724 3.42734 -1.06525 0.00439361 0.00495582 0.00330898 -0.999027 0.0436874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 4.17489e-05 0.019882 4.00038 0.0114456 0.00776619 +EDGE_SE3:QUAT 630 724 -0.584796 -0.974079 -0.0253823 0.00983779 0.00343276 -0.999115 0.040758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 4.10727e-05 0.039449 4.00156 0.0104769 0.00706211 +EDGE_SE3:QUAT 631 724 -4.99979 -0.845036 -0.0893832 0.0116511 -0.000282836 -0.999249 0.0369521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99946 -0.00013306 0.0466968 4.00216 -0.00457113 0.00601301 +EDGE_SE3:QUAT 725 726 4.49269 -0.0624159 -0.0396326 0.000737085 0.00735732 0.00532617 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00086 2.8596e-05 0.05882 3.99978 0.000157644 4.00075 +EDGE_SE3:QUAT 541 725 6.06993 2.12113 0.00786587 0.00417012 0.0027747 0.0172317 0.999839 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.68547e-05 0.0213255 3.99997 0.000181969 3.99893 +EDGE_SE3:QUAT 542 725 1.82537 2.24981 0.0295721 0.00415721 0.00167261 0.0210294 0.999769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.61258e-05 0.012323 3.99999 0.000126113 3.99827 +EDGE_SE3:QUAT 543 725 -2.3644 2.34255 -0.0600207 -0.000137684 -0.0136409 0.0256987 0.999577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00297 0.000122178 -0.109048 3.99926 -0.0014039 4.00033 +EDGE_SE3:QUAT 544 725 -6.53216 2.38927 -0.0742704 0.00076486 -0.0125102 0.0306751 0.999451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00251 7.71828e-05 -0.100277 3.99937 -0.00153837 3.99875 +EDGE_SE3:QUAT 628 725 3.41708 -1.46844 -0.038371 -0.00684343 0.0065909 -0.998634 0.0513763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000212728 -0.0274767 4.00046 0.0290011 0.010958 +EDGE_SE3:QUAT 629 725 -0.945892 -1.37291 -0.00120318 0.00165722 0.00155948 -0.998828 0.0483449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.71013e-06 0.00665349 4.00004 0.00556216 0.00936777 +EDGE_SE3:QUAT 630 725 -4.94441 -1.25549 -0.080881 0.00663002 0.00152817 -0.99894 0.0455177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 -7.79364e-06 0.0266029 4.00071 0.0036725 0.00846815 +EDGE_SE3:QUAT 726 727 3.9444 -0.100254 0.0172694 -0.0014746 0.00751754 -0.00538424 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00089 -5.15661e-05 0.060054 3.99977 -0.000163676 4.00079 +EDGE_SE3:QUAT 542 726 6.29993 2.37229 -0.0273792 0.00475744 0.00910352 0.0263804 0.999599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 0.000219151 0.0712638 3.99969 0.000942965 3.99849 +EDGE_SE3:QUAT 543 726 2.02604 2.51353 0.0164938 0.000555195 -0.00640291 0.0310309 0.999498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 1.63996e-05 -0.0513633 3.99984 -0.000797406 3.99681 +EDGE_SE3:QUAT 544 726 -2.11153 2.5999 -0.00694539 0.00136304 -0.00540366 0.0359136 0.999339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -4.2854e-06 -0.0437371 3.99988 -0.000787664 3.99532 +EDGE_SE3:QUAT 545 726 -6.37805 2.63876 0.0601583 0.00436191 -0.000105645 0.0412057 0.999141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -8.00617e-06 -0.00299734 4 -7.65409e-05 3.99321 +EDGE_SE3:QUAT 626 726 6.89242 -2.03419 0.0690054 0.00521906 0.00401271 -0.998142 0.060578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 4.72387e-05 0.0209978 4.00043 0.0133858 0.0148344 +EDGE_SE3:QUAT 627 726 2.97313 -1.9581 0.00105935 0.00221419 0.00654097 -0.998218 0.0592668 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.77263e-05 0.00891471 3.99995 0.0248887 0.0142256 +EDGE_SE3:QUAT 628 726 -1.03878 -1.86334 -0.015834 0.000746075 0.00643149 -0.998368 0.0567367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.59566e-05 0.00300835 3.99986 0.0251813 0.0130376 +EDGE_SE3:QUAT 629 726 -5.46888 -1.74177 -0.053568 0.0093132 0.00154427 -0.998521 0.0535331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -5.49228e-05 0.0374128 4.0014 0.00215631 0.0118153 +EDGE_SE3:QUAT 727 728 4.06564 -0.0992559 0.0481946 -0.0018632 0.000994813 -0.0068393 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.38115e-06 0.00780502 4 -2.65586e-05 3.99983 +EDGE_SE3:QUAT 543 727 6.0598 2.65254 0.0805387 -0.00140909 0.00111251 0.0255304 0.999672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.85213e-06 0.0093229 3.99999 0.000120765 3.99741 +EDGE_SE3:QUAT 544 727 1.79858 2.7805 0.0484844 -0.000598651 0.00210921 0.0304438 0.999534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.81809e-06 0.0170691 3.99998 0.000260761 3.99637 +EDGE_SE3:QUAT 545 727 -2.45882 2.86207 0.0695717 0.002547 0.0075192 0.035688 0.999331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 0.000121586 0.0589593 3.99979 0.00104886 3.99577 +EDGE_SE3:QUAT 546 727 -6.81116 2.90254 0.0927451 0.00305511 0.00740942 0.0416825 0.999099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 0.000139766 0.0576039 3.9998 0.00119337 3.99388 +EDGE_SE3:QUAT 626 727 3.01182 -2.40602 0.0410648 0.0127936 0.00630486 -0.998382 0.0550513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99929 0.000109873 0.0514105 4.00265 0.019428 0.0128802 +EDGE_SE3:QUAT 627 727 -0.96413 -2.32374 -0.005163 0.00974452 0.00870719 -0.998479 0.0535645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 0.000234925 0.0391562 4.00143 0.0304316 0.0120933 +EDGE_SE3:QUAT 628 727 -4.93871 -2.20893 -0.00920224 0.00818362 0.00827813 -0.998621 0.051188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000205746 0.0328724 4.00096 0.0295644 0.0109709 +EDGE_SE3:QUAT 728 729 4.09007 -0.104314 0.028185 -0.00142944 -0.00690489 -0.00662086 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 3.20102e-05 -0.0553582 3.99981 0.000181831 4.00059 +EDGE_SE3:QUAT 544 728 5.7976 2.92629 0.07447 -0.0022006 0.00305096 0.0238665 0.999708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -2.22105e-05 0.0250175 3.99996 0.000300482 3.99788 +EDGE_SE3:QUAT 545 728 1.5413 3.04858 0.0533761 0.000775604 0.00846966 0.0290958 0.99954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00113 7.58391e-05 0.0674172 3.99972 0.000981107 3.99775 +EDGE_SE3:QUAT 546 728 -2.65706 3.1316 0.0783218 0.00128057 0.00830277 0.0348377 0.999358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00107 9.88175e-05 0.0657816 3.99973 0.00114494 3.99623 +EDGE_SE3:QUAT 625 728 3.40389 -2.84298 0.021939 0.00741568 0.00627746 -0.998742 0.0491997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000129842 0.0297761 4.00083 0.022053 0.0100266 +EDGE_SE3:QUAT 626 728 -1.05246 -2.74762 -0.0192368 0.0137066 0.00781658 -0.998702 0.0484369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99918 0.000219462 0.0550219 4.00299 0.0258105 0.0103102 +EDGE_SE3:QUAT 627 728 -5.04605 -2.65531 -0.0390111 0.0106142 0.0104854 -0.998777 0.0471443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 0.000344151 0.0426085 4.00161 0.0377379 0.00970207 +EDGE_SE3:QUAT 729 730 3.9867 -0.10375 0.0243296 0.00199567 -0.0105669 -0.0036153 0.999936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00177 -9.40432e-05 -0.0844791 3.99955 0.000158176 4.00173 +EDGE_SE3:QUAT 545 729 5.72077 3.17407 0.0127709 -0.000242289 0.00156193 0.0222989 0.99975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.07769e-07 0.012551 3.99999 0.000140133 3.99805 +EDGE_SE3:QUAT 546 729 1.37816 3.30738 0.0360641 2.70824e-05 0.00136472 0.028252 0.9996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.4068e-06 0.0108956 3.99999 0.000153811 3.99684 +EDGE_SE3:QUAT 547 729 -2.67872 3.39093 0.0471842 0.00094529 0.00450121 0.0352824 0.999367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 3.35539e-05 0.0355449 3.99992 0.000624888 3.99534 +EDGE_SE3:QUAT 624 729 3.84088 -3.25761 -0.000861024 0.00477918 0.00696889 -0.999199 0.0391192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000123714 0.0191647 4.00023 0.0262787 0.00638612 +EDGE_SE3:QUAT 625 729 -0.743275 -3.14438 -0.0111615 0.000585833 0.00757854 -0.999062 0.042639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.63226e-05 0.00235474 3.99979 0.0299763 0.00749881 +EDGE_SE3:QUAT 626 729 -5.18153 -3.03839 -0.104039 0.00685335 0.00908158 -0.999057 0.0419049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000222472 0.0274926 4.00055 0.033882 0.00750088 +EDGE_SE3:QUAT 730 731 3.99996 -0.0953483 0.01364 0.000708409 0.00611085 -0.000871951 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 1.65467e-05 0.0489005 3.99985 -2.06937e-05 4.00059 +EDGE_SE3:QUAT 546 730 5.39549 3.41766 0.0428337 0.00212161 -0.00886755 0.0247497 0.999652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00126 -2.88162e-05 -0.0715248 3.99968 -0.000884119 3.99883 +EDGE_SE3:QUAT 547 730 1.30334 3.55114 0.0345965 0.00347084 -0.00574722 0.0314989 0.999481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -5.66564e-05 -0.0472255 3.99986 -0.000747696 3.99659 +EDGE_SE3:QUAT 548 730 -3.09608 3.68619 -0.0779783 -0.00304401 -0.0108507 0.0308445 0.999461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00179 0.000215091 -0.0855886 3.99955 -0.00132356 3.99802 +EDGE_SE3:QUAT 623 730 3.94335 -3.694 -0.0540794 -0.00364937 0.00712918 -0.999891 0.0124201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00010274 -0.0146018 3.99999 0.0288695 0.000878732 +EDGE_SE3:QUAT 624 730 -0.15878 -3.46417 -0.0165422 -0.00604402 0.00432169 -0.999337 0.0356461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -0.000128291 -0.0242211 4.00046 0.0189567 0.00531935 +EDGE_SE3:QUAT 625 730 -4.73086 -3.36705 0.00731729 -0.00969873 0.00549038 -0.99917 0.0391683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 -0.000286848 -0.0388827 4.00128 0.0249238 0.00667059 +EDGE_SE3:QUAT 731 732 4.25208 -0.0325579 0.0597504 0.00306077 0.0146437 0.0252384 0.99957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00333 0.000305963 0.116195 3.99916 0.00148073 4.00082 +EDGE_SE3:QUAT 547 731 5.30009 3.69571 0.0933297 0.0039918 0.000215508 0.0305176 0.999526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.5024e-07 0.000260699 4 -3.46935e-06 3.99627 +EDGE_SE3:QUAT 548 731 0.869836 3.83974 0.0201045 -0.00244214 -0.00465605 0.0296613 0.999546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 5.88549e-05 -0.0363327 3.99992 -0.000535638 3.99681 +EDGE_SE3:QUAT 549 731 -2.82914 4.08668 -0.0601953 -0.00626821 -0.00429112 -0.0181179 0.999807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 0.000104732 -0.0356751 3.99992 0.00032436 3.99901 +EDGE_SE3:QUAT 622 731 3.32176 -4.1329 -0.0499397 -0.00767477 -0.0136487 0.996838 0.0779041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000374548 0.0309348 3.99983 0.0585291 0.0253778 +EDGE_SE3:QUAT 623 731 -0.0509685 -3.68386 -0.00874469 0.00255201 0.00658053 -0.999911 0.011293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.91834e-05 0.0102107 3.99994 0.0260836 0.000706308 +EDGE_SE3:QUAT 624 731 -4.16333 -3.63781 0.047498 0.000121562 0.00395351 -0.999394 0.0345902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.17525e-06 0.000488457 3.99994 0.015733 0.00484794 +EDGE_SE3:QUAT 732 733 4.21828 0.174148 0.0166697 0.00302388 -0.00519247 0.0848936 0.996372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 -7.4347e-06 -0.0441616 3.99988 -0.00191012 3.97166 +EDGE_SE3:QUAT 548 732 5.12587 4.05595 0.122155 7.97697e-05 0.0100894 0.0547724 0.998448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00161 0.000136211 0.0803282 3.9996 0.00219862 3.98961 +EDGE_SE3:QUAT 549 732 1.43576 3.89848 0.0391024 -0.00323956 0.0103646 0.00686626 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00169 -0.000117273 0.0832078 3.99957 0.000277886 4.00154 +EDGE_SE3:QUAT 550 732 -1.99816 4.10997 0.0218707 -0.00164014 0.0039511 -0.0881292 0.9961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -5.34513e-05 0.0295169 3.99995 -0.00127049 3.96915 +EDGE_SE3:QUAT 551 732 -4.93494 5.44788 0.0842236 0.00208144 0.0091804 -0.248143 0.968678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 -0.000434379 0.07273 3.99976 -0.00899012 3.75502 +EDGE_SE3:QUAT 620 732 5.18965 -5.13207 -0.0251606 -0.00557028 -0.00679164 0.931523 0.363576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.2418e-05 0.0236338 3.9998 0.0326756 0.529197 +EDGE_SE3:QUAT 621 732 2.46929 -3.82089 -0.0399119 -0.00401333 -0.0108216 0.978392 0.206438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.30541e-05 0.0162855 3.99951 0.0450863 0.171064 +EDGE_SE3:QUAT 622 732 -0.877743 -3.43444 -0.0498924 -0.0223312 -0.00938744 0.998309 0.0528458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99822 0.00140002 0.0896941 4.00705 0.0468267 0.0137359 +EDGE_SE3:QUAT 623 732 -4.3024 -3.74692 0.0252407 0.0174284 0.00367452 -0.999179 0.0363959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99876 -9.31714e-06 0.0698423 4.0049 0.00959548 0.00654317 +EDGE_SE3:QUAT 733 734 4.25313 0.499846 0.0219355 -0.00103074 -0.00554331 0.154717 0.987943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 0.000122285 -0.040884 3.99991 -0.00307322 3.90467 +EDGE_SE3:QUAT 549 733 5.62544 4.12989 -0.0295591 0.000609982 0.00542122 0.0918038 0.995762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 7.49651e-05 0.0421584 3.99989 0.00191742 3.96673 +EDGE_SE3:QUAT 550 733 2.17063 3.53641 0.00255449 0.00121516 -0.00127209 -0.00348735 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -6.27635e-06 -0.0101257 3.99999 1.76734e-05 3.99998 +EDGE_SE3:QUAT 551 733 -1.15393 3.5686 0.0171552 0.00456367 0.00328849 -0.16537 0.986216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 1.79095e-05 0.034129 3.99992 -0.00303973 3.8909 +EDGE_SE3:QUAT 552 733 -3.71861 4.77497 -0.00821171 0.005885 0.00256196 -0.362883 0.931813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -4.95865e-05 0.0399636 3.99991 -0.00851535 3.47366 +EDGE_SE3:QUAT 619 733 5.27752 -3.58631 -0.013746 -0.00364343 -0.00324002 0.903046 0.429516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.81909e-05 0.0159633 3.99995 0.0175949 0.738096 +EDGE_SE3:QUAT 620 733 1.98405 -2.40226 -0.0345815 -0.000373903 -0.00544986 0.958885 0.283741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.45179e-05 0.000668925 3.99993 0.018318 0.32213 +EDGE_SE3:QUAT 621 733 -1.44681 -2.26881 -0.0371287 0.000612245 -0.0088157 0.992401 0.122731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -8.65548e-05 -0.00263483 3.99976 0.0333492 0.060536 +EDGE_SE3:QUAT 622 733 -5.08739 -3.15219 -0.215161 0.0175956 0.00509999 -0.99933 0.0316963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99873 0.000125897 0.0704787 4.00498 0.0159169 0.00532542 +EDGE_SE3:QUAT 734 735 4.11979 0.559263 -0.0082947 0.00173831 0.000695036 0.1706 0.985339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.30516e-07 0.00182968 4 4.78806e-05 3.88358 +EDGE_SE3:QUAT 551 734 3.02793 2.64102 0.0111507 0.00298425 -0.00268155 -0.0106878 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -3.30368e-05 -0.0210663 3.99997 0.000112396 3.99965 +EDGE_SE3:QUAT 552 734 -0.255705 2.23755 -0.0150742 0.00307983 -0.00304605 -0.214553 0.976703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.19861e-05 -0.0150189 4 0.0012661 3.81592 +EDGE_SE3:QUAT 553 734 -3.23695 3.39161 -0.0169106 -0.00140448 -0.00205736 -0.46459 0.885522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -4.86212e-05 -0.0181326 4 0.00432058 3.1367 +EDGE_SE3:QUAT 618 734 6.12846 -1.6482 -0.00269303 0.00105 -0.00418308 0.915559 0.402161 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.98334e-06 -0.00726576 4.00008 0.00753254 0.646974 +EDGE_SE3:QUAT 619 734 2.20502 -0.590252 -0.0128585 0.000352174 -0.00581503 0.958732 0.284253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.76312e-05 -0.00263745 3.99997 0.0179609 0.323292 +EDGE_SE3:QUAT 620 734 -1.86349 -0.490765 -0.00863077 0.00378429 -0.00776705 0.991212 0.131999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000100221 -0.0156709 4.00019 0.0257993 0.0699283 +EDGE_SE3:QUAT 621 734 -5.70148 -1.69646 -0.011563 -0.00475235 0.0102815 -0.999417 0.0321976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000182528 -0.0190391 3.99987 0.0422442 0.00468404 +EDGE_SE3:QUAT 735 736 4.05189 0.533347 0.00462661 -0.000833785 0.00695402 0.160976 0.986933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 0.000163432 0.0550757 3.99983 0.00441832 3.8971 +EDGE_SE3:QUAT 552 735 3.70806 1.01239 -0.00464389 0.00440555 -0.00318561 -0.0446049 0.99899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -5.83182e-05 -0.0230538 3.99997 0.000497022 3.99217 +EDGE_SE3:QUAT 553 735 -0.446502 0.324936 -0.00597272 8.94374e-07 -0.00179281 -0.306725 0.951796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.96933e-05 -0.0123639 4 0.00178516 3.62372 +EDGE_SE3:QUAT 554 735 -4.17126 1.63276 -0.0398064 0.00539395 -0.00472399 -0.533244 0.845931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 6.55102e-05 0.00509411 3.99997 -0.00603494 2.86256 +EDGE_SE3:QUAT 617 735 7.18352 0.370528 0.0230206 5.16367e-05 -5.37034e-06 0.954785 0.297298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.63046e-08 -0.000233197 4 -9.50725e-05 0.353544 +EDGE_SE3:QUAT 618 735 2.92249 0.996546 0.00298574 0.000435185 -0.00237475 0.970751 0.240075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.65399e-06 -0.0021475 4 0.00737065 0.23056 +EDGE_SE3:QUAT 619 735 -1.538 1.19225 -0.0079556 -0.000777981 -0.00420843 0.99318 0.116509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.56445e-06 0.00312141 3.99993 0.0169803 0.0543727 +EDGE_SE3:QUAT 620 735 -5.9761 0.0572016 0.0153477 -0.00187709 0.00674566 -0.999208 0.0391794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.85434e-05 -0.00752283 3.99985 0.0274663 0.00634314 +EDGE_SE3:QUAT 736 737 4.16822 0.476717 0.034335 -0.00404513 -0.00133878 0.133025 0.991104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 5.13724e-06 -0.00404597 4 -0.000119622 3.92922 +EDGE_SE3:QUAT 553 736 3.1579 -1.61112 0.0126866 0.00120695 0.00519548 -0.149122 0.988804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -7.47752e-05 0.0423171 3.9999 -0.00317397 3.9115 +EDGE_SE3:QUAT 554 736 -1.9488 -1.79998 -0.0139334 0.00766484 0.000803504 -0.390166 0.920712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 3.53766e-05 0.0372639 3.99989 -0.00946516 3.39141 +EDGE_SE3:QUAT 555 736 -6.46863 0.426952 0.0590903 0.00118954 0.0024157 -0.600888 0.799329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -6.82344e-05 0.0163829 4.00003 -0.00436018 2.5558 +EDGE_SE3:QUAT 617 736 3.54047 2.23308 0.0291612 -0.00679111 0.00124138 0.990189 0.139563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000124018 0.0279729 4.00074 0.00271046 0.0781123 +EDGE_SE3:QUAT 618 736 -0.903687 2.42288 0.0166697 -0.0070814 -0.00176216 0.996714 0.0806703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000138788 0.0285934 4.00073 0.0114778 0.0262695 +EDGE_SE3:QUAT 619 736 -5.58616 1.62141 -0.0102395 0.00842202 0.00413529 -0.998966 0.044487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 6.56006e-05 0.0337898 4.00114 0.013473 0.00824789 +EDGE_SE3:QUAT 737 738 4.26914 0.408802 0.0301531 0.000893632 -0.00176708 0.11291 0.993603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.5398e-06 -0.0150679 3.99999 -0.000868257 3.94906 +EDGE_SE3:QUAT 554 737 1.29235 -4.46527 -0.00539994 0.00338916 -3.01968e-05 -0.264392 0.964409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.68907e-05 0.010035 3.99999 -0.00180032 3.72041 +EDGE_SE3:QUAT 555 737 -4.86443 -3.44014 0.06457 -0.00238085 0.00342605 -0.489162 0.872183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.86151e-05 0.00643877 4.00001 0.000479515 3.04288 +EDGE_SE3:QUAT 616 737 3.73721 2.82676 0.0217057 -0.00628615 -0.00246398 0.999759 0.0208982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 8.03491e-05 0.0251607 4.00059 0.010898 0.00193497 +EDGE_SE3:QUAT 617 737 -0.582198 2.94793 -0.000539841 -0.00588222 -0.00198171 0.99996 0.00639431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 5.17284e-05 0.0235301 4.00053 0.00822846 0.000318899 +EDGE_SE3:QUAT 618 737 -5.08174 2.62858 -0.0131237 0.00599679 0.00473431 -0.998594 0.0524632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 7.28682e-05 0.0240913 4.00055 0.0163003 0.0112217 +EDGE_SE3:QUAT 738 739 4.04383 0.205779 0.0252 -0.00646333 -0.00463911 0.0511483 0.998659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 0.000124346 -0.0330067 3.99994 -0.000811994 3.98981 +EDGE_SE3:QUAT 555 738 -2.31201 -6.8599 0.0792482 -0.00226936 0.00167372 -0.387385 0.921914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.48752e-06 0.00099768 4 0.000696648 3.39973 +EDGE_SE3:QUAT 615 738 3.72085 2.52079 0.0118994 0.00556547 0.000546221 -0.995563 0.0939263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -5.80286e-05 0.0225578 4.00049 -0.00200876 0.0354179 +EDGE_SE3:QUAT 616 738 -0.524937 2.61488 0.00208974 0.00488186 0.00102398 -0.995749 0.0919679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -3.37349e-05 0.0197797 4.00039 0.000448092 0.0339311 +EDGE_SE3:QUAT 617 738 -4.84572 2.60012 -0.020315 0.0042922 0.000243594 -0.994319 0.106353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -4.25734e-05 0.0174598 4.00029 -0.00266403 0.0453226 +EDGE_SE3:QUAT 739 740 4.12896 -0.124645 -0.00899146 0.00347464 0.015214 -0.0183768 0.999709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0037 0.000110636 0.122515 3.99906 -0.00111113 4.0024 +EDGE_SE3:QUAT 614 739 4.11973 1.49017 -0.00110367 -0.00140849 0.00657977 -0.989144 0.146798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.46803e-05 -0.00564661 3.99982 0.0265297 0.0863861 +EDGE_SE3:QUAT 615 739 -0.200006 1.56886 -0.0046818 0.000441131 0.00635444 -0.989462 0.144653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.92531e-05 0.0019732 3.99989 0.0235979 0.083841 +EDGE_SE3:QUAT 616 739 -4.46879 1.6808 -0.0110674 -0.000147005 0.00692467 -0.989727 0.142804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.69544e-05 -0.000444107 3.99983 0.0264607 0.0817507 +EDGE_SE3:QUAT 740 741 4.05025 -0.217123 0.0175392 -0.00252791 -0.0034712 -0.0515037 0.998664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 2.13994e-05 -0.0292199 3.99995 0.000764233 3.9896 +EDGE_SE3:QUAT 613 740 4.33888 0.312573 0.0316918 0.00707779 0.00668899 -0.991409 0.130437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 3.00102e-05 0.0291419 4.00089 0.0183701 0.0683588 +EDGE_SE3:QUAT 614 740 0.22375 0.413645 -0.000264187 0.0140081 0.0050636 -0.991588 0.128577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99918 -0.000352716 0.0574834 4.00332 0.00525266 0.0669759 +EDGE_SE3:QUAT 615 740 -4.11247 0.51748 -0.0178448 0.0160687 0.00460324 -0.991804 0.126669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99895 -0.000520834 0.0658679 4.0043 0.00165212 0.0652838 +EDGE_SE3:QUAT 741 742 4.24065 -0.366175 0.0126544 -4.14434e-05 0.000824977 -0.0638819 0.997957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.16267e-06 0.00652779 4 -0.000207736 3.98369 +EDGE_SE3:QUAT 612 741 4.62132 -0.600304 0.00619205 0.0031709 0.0102382 -0.996675 0.0807733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000162896 0.0128521 3.99988 0.0382524 0.0265074 +EDGE_SE3:QUAT 613 741 0.363011 -0.510968 -0.00579373 0.00301367 0.00905996 -0.996792 0.0794666 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000131844 0.012206 3.99993 0.0337666 0.0255843 +EDGE_SE3:QUAT 614 741 -3.72355 -0.398182 -0.095942 0.010192 0.00750573 -0.996924 0.0773397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000120504 0.0411578 4.0017 0.0233201 0.024489 +EDGE_SE3:QUAT 742 743 4.19336 -0.232039 0.0104495 0.000988302 -0.00075724 -0.0356702 0.999363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.14529e-06 -0.00562369 4 9.77278e-05 3.99492 +EDGE_SE3:QUAT 611 742 4.82326 -1.01041 0.00902893 0.00387218 0.00998194 -0.999787 0.0176245 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000161538 0.0154985 3.99987 0.0393527 0.00168985 +EDGE_SE3:QUAT 612 742 0.351648 -0.906637 -0.00724679 0.00326817 0.010388 -0.99979 0.017355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000145656 0.0130811 3.99977 0.0410677 0.00166937 +EDGE_SE3:QUAT 613 742 -3.8868 -0.815334 -0.020378 0.0032559 0.00903355 -0.999832 0.0155955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000123397 0.0130301 3.99987 0.035707 0.00133416 +EDGE_SE3:QUAT 743 744 4.1627 -0.186763 0.0185246 -7.9178e-08 0.00107222 -0.0191814 0.999815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.29236e-07 0.00857307 4 -8.22075e-05 3.99855 +EDGE_SE3:QUAT 610 743 4.99471 -1.02518 0.0192183 -0.00558521 -0.00947081 0.999752 0.0193622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000210976 0.0223557 4.00009 0.0387169 0.00199943 +EDGE_SE3:QUAT 611 743 0.599265 -0.919604 -0.0089167 -0.00275167 -0.00913566 0.999794 0.0179308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.13294e-05 0.0110128 3.99977 0.0369076 0.00165705 +EDGE_SE3:QUAT 612 743 -3.81578 -0.81422 -0.01722 -0.00222242 -0.00946974 0.999777 0.0187499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.24902e-05 0.00889497 3.9997 0.038178 0.00179056 +EDGE_SE3:QUAT 744 745 4.2349 -0.125718 0.0219729 0.00299388 -0.000154213 -0.00702956 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -1.34535e-06 -0.000981059 4 3.15341e-06 3.9998 +EDGE_SE3:QUAT 609 744 5.27494 -0.796622 0.0202168 -0.00500174 -0.00769117 0.999029 0.0430893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000154899 0.0200595 4.00009 0.0323457 0.00778952 +EDGE_SE3:QUAT 610 744 0.858706 -0.672901 -0.00450044 -0.00644075 -0.00945577 0.999187 0.0386503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000248778 0.0258199 4.00019 0.0396764 0.00653634 +EDGE_SE3:QUAT 611 744 -3.54255 -0.576589 -0.0123293 -0.00377322 -0.00931804 0.999261 0.0370936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000124575 0.0151221 3.99982 0.0382628 0.00592747 +EDGE_SE3:QUAT 745 746 4.21796 -0.117722 0.0207168 0.00287602 -0.00191083 -0.00240326 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.20326e-05 -0.0152036 3.99999 1.84863e-05 4.00003 +EDGE_SE3:QUAT 608 745 5.37408 -0.491823 0.0204482 -0.00515115 -0.00784576 0.997976 0.0628891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000160828 0.0207129 4.00006 0.0336572 0.016212 +EDGE_SE3:QUAT 609 745 1.05935 -0.303754 0.00416076 -0.00459391 -0.00485279 0.998721 0.0501171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000101548 0.0184406 4.00019 0.0211285 0.010244 +EDGE_SE3:QUAT 610 745 -3.38471 -0.213821 -0.0284826 -0.00610507 -0.00649533 0.998923 0.0455445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000178779 0.0244929 4.00034 0.028071 0.0086448 +EDGE_SE3:QUAT 746 747 3.96393 -0.0756146 0.0172075 0.00317485 0.00079293 0.0162939 0.999862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.96027e-06 0.00572017 4 4.49501e-05 3.99895 +EDGE_SE3:QUAT 607 746 5.42881 -0.0719165 0.0258248 -0.00395374 -0.00568922 0.996533 0.0829132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.00598e-05 0.0159522 4.00003 0.0249723 0.0277193 +EDGE_SE3:QUAT 608 746 1.25254 0.146772 0.00309074 -0.00314689 -0.00491405 0.997826 0.0656386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.06551e-05 0.012658 4.00001 0.0210908 0.0173855 +EDGE_SE3:QUAT 609 746 -3.07093 0.232583 -0.00923181 -0.00282215 -0.00191409 0.998583 0.0531104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.91997e-05 0.011334 4.0001 0.00879847 0.0113345 +EDGE_SE3:QUAT 747 748 4.1367 0.133149 0.0191462 -0.00227686 -0.00496235 0.0785666 0.996894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 8.3515e-05 -0.0371963 3.99992 -0.00142982 3.97565 +EDGE_SE3:QUAT 606 747 5.62303 -0.0216901 0.0305521 -0.00489465 -0.00434896 0.990015 0.140813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000117301 0.0200561 4.00016 0.0219458 0.0795371 +EDGE_SE3:QUAT 607 747 1.53536 0.660298 0.0135653 -0.00459427 -0.00216534 0.997758 0.0667299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 6.80578e-05 0.0184944 4.00028 0.011008 0.0179278 +EDGE_SE3:QUAT 608 747 -2.6455 0.74397 0.0049633 -0.00389844 -0.00184912 0.998779 0.0492082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 4.42643e-05 0.0156486 4.00021 0.00888341 0.00976693 +EDGE_SE3:QUAT 609 747 -6.98399 0.729653 -0.0115917 -0.00353709 0.00171039 0.999339 0.0361539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.37089e-05 0.0141766 4.0002 -0.00579789 0.00528713 +EDGE_SE3:QUAT 748 749 4.27628 0.616618 0.00421387 0.00136683 0.0147563 0.188865 0.981891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00295 0.00095805 0.108833 3.99942 0.0100044 3.86027 +EDGE_SE3:QUAT 605 748 6.15669 -0.284755 -0.0527592 0.00938916 -0.00858929 0.97783 0.209012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000200453 -0.0405583 4.00178 0.0156559 0.175245 +EDGE_SE3:QUAT 606 748 1.62128 1.00466 0.0128198 -0.000329096 -0.00714583 0.998026 0.0624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.6061e-05 0.00131008 3.9998 0.0284684 0.0157789 +EDGE_SE3:QUAT 607 748 -2.57408 1.08127 -0.00441433 -9.39292e-05 0.00472064 -0.999914 0.0122557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.11512e-07 -0.000375734 3.99991 0.0188845 0.000690016 +EDGE_SE3:QUAT 608 748 -6.80749 1.02613 -0.00900599 -0.00112202 0.00423971 -0.999547 0.0297824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.53906e-05 -0.00449325 3.99994 0.0171883 0.00362694 +EDGE_SE3:QUAT 749 750 4.07218 0.675834 0.00455054 0.00167986 -0.00177132 0.194271 0.980945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 4.98882e-06 -0.0171939 3.99998 -0.00177003 3.84911 +EDGE_SE3:QUAT 487 749 2.24433 -7.00847 0.0452911 -0.00410841 0.00334476 0.78101 0.624495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 0.000273565 0.0293651 4.00023 0.010224 1.56026 +EDGE_SE3:QUAT 604 749 6.41943 -0.603441 0.0393 -0.00391851 -0.00864365 0.981694 0.190231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.98898e-05 0.0160266 3.99972 0.0372329 0.145175 +EDGE_SE3:QUAT 605 749 2.00379 0.904567 0.0364454 -0.00646227 -0.00572263 0.999753 0.020462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000162149 0.0258659 4.0005 0.0239288 0.00198528 +EDGE_SE3:QUAT 606 749 -2.6505 0.9264 0.0051428 0.0164838 0.00431873 -0.991714 0.127328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99891 -0.000576098 0.0675805 4.0045 5.27416e-05 0.0660106 +EDGE_SE3:QUAT 607 749 -6.80742 0.366439 -0.0090799 0.015606 0.00303547 -0.979501 0.200813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9992 -0.0010045 0.0662792 4.00384 -0.0131525 0.162486 +EDGE_SE3:QUAT 750 751 4.2522 0.714861 0.00976297 -0.000762961 -0.00221073 0.177747 0.984074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 2.23856e-05 -0.0152614 3.99999 -0.00128286 3.87368 +EDGE_SE3:QUAT 486 750 5.40721 -2.77748 0.00873548 -0.00215738 -0.000178476 0.930161 0.367146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.99175e-05 0.0101202 4.00004 0.00596758 0.539221 +EDGE_SE3:QUAT 487 750 0.694499 -3.18592 0.00424968 -0.000868595 0.00421448 0.887494 0.460799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.10929e-05 0.00769174 4.00008 -0.00608574 0.849384 +EDGE_SE3:QUAT 488 750 -4.77545 -2.10789 -0.0166729 -0.00173724 0.00565117 0.769676 0.638408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000207823 0.0214716 4.00023 0.00204148 1.63043 +EDGE_SE3:QUAT 603 750 6.57106 -1.21739 0.0185976 -0.00373446 -0.00669389 0.987195 0.159336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.06065e-05 0.0152802 3.99988 0.0297307 0.101837 +EDGE_SE3:QUAT 604 750 2.39237 0.299197 0.0134762 0.00310405 0.00657936 -0.999964 0.00428177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.21635e-05 0.0124173 3.99999 0.0262108 0.000283634 +EDGE_SE3:QUAT 605 750 -2.06064 0.39809 -0.0197477 0.00544898 0.0026568 -0.984719 0.174047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -7.79959e-05 0.0228751 4.00053 0.00247381 0.121306 +EDGE_SE3:QUAT 606 750 -6.43856 -0.741563 -0.12865 0.0152424 -0.000663751 -0.948016 0.317858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.00143632 0.06934 4.00254 -0.0368978 0.40577 +EDGE_SE3:QUAT 682 750 2.26502 5.29782 0.116847 0.0104166 0.00618001 -0.626987 0.778936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -0.00118153 0.0812403 4.00028 -0.0288509 2.42918 +EDGE_SE3:QUAT 683 750 -3.56524 5.20773 0.151454 0.0119498 0.00893326 -0.503582 0.863818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00224 -0.00142526 0.106159 3.99989 -0.0298321 2.98843 +EDGE_SE3:QUAT 751 752 4.48942 0.513217 0.0280303 -0.00620561 0.00919048 0.11259 0.99358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00146 7.57651e-06 0.0804697 3.99959 0.00465076 3.95091 +EDGE_SE3:QUAT 485 751 6.02576 -0.271365 -0.0180723 0.00142224 0.000112639 0.985413 0.170173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.16402e-06 -0.00592624 4.00003 -0.00229845 0.115846 +EDGE_SE3:QUAT 486 751 1.82456 -0.353691 0.00520632 -0.000158044 -0.00106063 0.980688 0.195577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.07705e-06 0.000603917 4 0.00408013 0.153007 +EDGE_SE3:QUAT 487 751 -2.30619 -0.0652843 -0.00345372 0.00120912 0.00227504 0.95541 0.295271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.86738e-06 -0.00495806 3.99998 -0.00978546 0.348772 +EDGE_SE3:QUAT 488 751 -6.20165 1.97527 -0.0443421 0.000113495 0.00357547 0.870892 0.491462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.52756e-06 0.00280903 4.00002 -0.00677709 0.966166 +EDGE_SE3:QUAT 602 751 6.3201 -1.58178 -0.0216564 0.000924545 -0.000336539 0.994363 0.106022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.01585e-06 -0.00376322 4.00001 0.000533116 0.0449662 +EDGE_SE3:QUAT 603 751 2.30695 -0.539739 -0.00216923 0.00268785 0.00694458 -0.999797 0.0187141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.82138e-05 0.0107581 3.99994 0.0273523 0.00161693 +EDGE_SE3:QUAT 604 751 -1.86154 -0.419165 -0.0143133 0.00213163 0.00683707 -0.983256 0.182091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 6.78197e-05 0.00927042 4.00005 0.0221066 0.132779 +EDGE_SE3:QUAT 605 751 -5.82712 -1.71206 -0.0629552 0.00345785 0.00195904 -0.937936 0.346785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -9.19632e-05 0.016747 4.00021 -0.00285778 0.481118 +EDGE_SE3:QUAT 682 751 3.83733 1.26477 0.0365866 0.00931591 0.00291024 -0.47785 0.878387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 -0.000231339 0.0610809 3.99983 -0.0179696 3.08756 +EDGE_SE3:QUAT 683 751 -0.878697 1.81764 0.0472973 0.011417 0.00512484 -0.341645 0.939746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 -0.000144204 0.0772195 3.99963 -0.015379 3.53459 +EDGE_SE3:QUAT 684 751 -5.21711 1.29109 -0.156574 0.0123517 -0.012993 -0.242189 0.970063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.000732957 -0.060418 3.99996 0.00551371 3.76622 +EDGE_SE3:QUAT 752 753 4.37219 0.101325 -0.00303816 -0.000961869 0.000767485 0.0309691 0.99952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.69883e-06 0.00648829 4 0.000102253 3.99617 +EDGE_SE3:QUAT 484 752 5.76819 0.711614 0.0414731 -0.0047838 -0.00401556 0.998667 0.0512284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 9.51109e-05 0.0192066 4.00025 0.0179142 0.0106703 +EDGE_SE3:QUAT 485 752 1.6361 0.770823 0.0233496 -0.00881667 -0.00453464 0.998283 0.0577234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000249279 0.0354366 4.00104 0.0220543 0.0137648 +EDGE_SE3:QUAT 486 752 -2.50732 0.907613 0.0297808 -0.0106703 -0.00520847 0.996419 0.0837153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000406144 0.043106 4.00146 0.0275816 0.0286916 +EDGE_SE3:QUAT 487 752 -6.2908 2.06376 0.0342667 -0.00891381 -0.000634954 0.982596 0.185538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000341931 0.0374171 4.00109 0.0151065 0.138115 +EDGE_SE3:QUAT 601 752 5.98589 -1.57291 0.0247781 -0.00384383 -0.00648778 0.998809 0.0482028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.70162e-05 0.015424 4.00001 0.0272805 0.00954008 +EDGE_SE3:QUAT 602 752 1.81732 -1.11317 0.0166548 0.00910566 0.00571383 -0.999919 0.00687256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000196303 0.0364253 4.00121 0.0223619 0.000645635 +EDGE_SE3:QUAT 603 752 -2.1495 -1.18868 -0.00797564 0.0127369 0.0131114 -0.991196 0.131138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99907 0.000160828 0.0524743 4.00289 0.0371087 0.0698442 +EDGE_SE3:QUAT 604 752 -5.86829 -2.4961 -0.0247877 0.0108867 0.0139948 -0.956323 0.291774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99915 -0.000564426 0.0515091 4.00296 0.021191 0.341412 +EDGE_SE3:QUAT 682 752 6.69753 -2.2173 0.00262353 0.00882795 0.0130305 -0.376072 0.926457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00323 -0.00149237 0.11911 3.99958 -0.0233382 3.43782 +EDGE_SE3:QUAT 683 752 2.89569 -0.675833 0.00516787 0.00929963 0.0147762 -0.233587 0.972179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00413 -0.000884413 0.133917 3.99903 -0.0162449 3.78623 +EDGE_SE3:QUAT 684 752 -1.02623 -0.382765 -0.0360818 0.00674447 -0.00360903 -0.131063 0.991345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -6.67119e-05 -0.017644 3.99999 0.000909177 3.93136 +EDGE_SE3:QUAT 685 752 -5.17771 -0.641348 -0.0382791 0.00234403 -0.00258258 -0.0646619 0.997901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -3.00855e-05 -0.0187176 3.99998 0.000584514 3.98336 +EDGE_SE3:QUAT 753 754 4.07392 -0.043239 -0.0124961 0.00154472 -0.00472609 0.0114713 0.999922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -2.32199e-05 -0.0380168 3.99991 -0.00021766 3.99983 +EDGE_SE3:QUAT 483 753 5.64623 0.992399 0.0608805 -0.0072066 -0.00899061 0.999759 0.0186698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000269056 0.0288442 4.00045 0.0370156 0.0019449 +EDGE_SE3:QUAT 484 753 1.41947 1.05643 -0.000229731 -0.00554037 -0.00482721 0.999759 0.0206824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000117662 0.0221759 4.00037 0.0202076 0.00193616 +EDGE_SE3:QUAT 485 753 -2.69647 1.18586 -0.0565046 -0.00955984 -0.00475899 0.999577 0.0270342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000234423 0.0382808 4.00131 0.0210774 0.00340112 +EDGE_SE3:QUAT 486 753 -6.79694 1.54653 -0.0673498 -0.0117017 -0.00498565 0.998507 0.053113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000386563 0.0469996 4.00193 0.0247782 0.0119915 +EDGE_SE3:QUAT 600 753 5.6701 -1.38218 0.0355014 -0.00406236 -0.00707555 0.999551 0.0288286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000113354 0.0162695 4.00002 0.0291811 0.00360364 +EDGE_SE3:QUAT 601 753 1.62877 -1.24491 -0.00665647 -0.00457959 -0.00739653 0.999812 0.0173465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000136006 0.0183277 4.00009 0.0302016 0.0015157 +EDGE_SE3:QUAT 602 753 -2.50889 -1.26275 -0.069094 0.0100908 0.00646955 -0.999237 0.037178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000177452 0.0404487 4.00157 0.0228043 0.00606861 +EDGE_SE3:QUAT 603 753 -6.28697 -2.3929 -0.136251 0.0138285 0.0134359 -0.986748 0.16111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9989 -5.42778e-05 0.0578618 4.00362 0.0329645 0.104973 +EDGE_SE3:QUAT 683 753 6.79947 -2.57629 -0.140879 0.00880537 0.0153691 -0.203464 0.978922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00434 -0.000765799 0.13644 3.99895 -0.0143224 3.83906 +EDGE_SE3:QUAT 684 753 3.22075 -1.4411 -0.0151507 0.0058118 -0.0031825 -0.0999901 0.994966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -6.03191e-05 -0.0181511 3.99999 0.000785747 3.96009 +EDGE_SE3:QUAT 685 753 -0.847973 -1.12381 -0.0207727 0.00121112 -0.00198062 -0.0339293 0.999422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.22106e-05 -0.015325 3.99999 0.000257158 3.99545 +EDGE_SE3:QUAT 686 753 -5.31762 -1.09513 0.0951561 -0.00346339 0.00777427 -0.0160653 0.999835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0009 -0.000129101 0.061514 3.99977 -0.000497515 3.99991 +EDGE_SE3:QUAT 754 755 4.28061 -0.0611521 0.00641849 -0.000427699 0.00311357 0.00924857 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.18208e-06 0.0249537 3.99996 0.000115373 3.99981 +EDGE_SE3:QUAT 482 754 5.88565 1.06645 -0.005463 0.00210649 -0.00860652 0.999909 0.0101996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.73472e-05 -0.0084283 3.99978 0.0342449 0.00072711 +EDGE_SE3:QUAT 483 754 1.58489 1.18321 -0.00757116 -0.00252436 -0.00732103 0.999944 0.00715791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.18875e-05 0.010099 3.99988 0.0294251 0.000446916 +EDGE_SE3:QUAT 484 754 -2.64924 1.27602 -0.0558669 -0.000892442 -0.0030444 0.999955 0.00892852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.03627e-05 0.00357022 3.99997 0.0122389 0.000359512 +EDGE_SE3:QUAT 485 754 -6.72085 1.44099 -0.143436 -0.00482287 -0.00281233 0.999856 0.0160016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.19659e-05 0.0192989 4.00033 0.0118608 0.00115251 +EDGE_SE3:QUAT 599 754 5.88226 -1.18271 0.00829056 -0.000655246 -0.00395935 0.999842 0.017323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.33614e-06 0.00262205 3.99994 0.0159162 0.00126541 +EDGE_SE3:QUAT 600 754 1.60835 -1.09727 -0.0105941 0.00036241 -0.00567509 0.999836 0.0172078 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.25609e-05 -0.00145061 3.99988 0.0226334 0.00131307 +EDGE_SE3:QUAT 601 754 -2.42387 -1.0556 -0.0584621 -5.6646e-05 -0.00586003 0.999966 0.00587606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.86574e-07 0.000226588 3.99986 0.0234404 0.000275498 +EDGE_SE3:QUAT 602 754 -6.5492 -1.51702 -0.16244 0.00568341 0.00457061 -0.998784 0.048761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 7.04329e-05 0.0228187 4.00049 0.0159649 0.00970493 +EDGE_SE3:QUAT 685 754 3.21959 -1.44607 -0.0178946 0.0029155 -0.00685408 -0.0218366 0.999734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0007 -0.000102494 -0.0540375 3.99982 0.000590571 3.99882 +EDGE_SE3:QUAT 686 754 -1.24378 -1.268 0.0206136 -0.00160327 0.00278244 -0.00442509 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.85715e-05 0.0221743 3.99997 -4.92984e-05 4.00004 +EDGE_SE3:QUAT 687 754 -5.20218 -1.19627 0.0124587 -0.000684577 0.00138835 -0.00117524 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.85169e-06 0.0110972 3.99999 -6.55078e-06 4.00003 +EDGE_SE3:QUAT 755 756 4.30448 -0.0896963 0.0569835 -7.03394e-05 0.00146415 0.00434579 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.88425e-07 0.0117166 3.99999 2.54584e-05 3.99996 +EDGE_SE3:QUAT 481 755 5.97287 1.06698 0.0103166 -0.00457768 -0.00762408 0.999914 0.00968126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000139783 0.0183147 4.00009 0.0308462 0.000696652 +EDGE_SE3:QUAT 482 755 1.6408 1.19917 0.0183604 -0.00126368 -0.00906375 0.999957 0.00135493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.49685e-05 0.00505536 3.9997 0.0362674 0.000342587 +EDGE_SE3:QUAT 483 755 -2.66272 1.30968 -0.0177711 0.00584742 0.00731665 -0.999954 0.00213406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000170349 0.0233913 4.00034 0.0291712 0.000367719 +EDGE_SE3:QUAT 484 755 -6.82226 1.42668 -0.0509827 -0.00454117 -0.00302234 0.999985 0.000302593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 5.50422e-05 0.0181647 4.00029 0.0121017 0.000119466 +EDGE_SE3:QUAT 598 755 6.08054 -1.08518 0.00941958 -0.00478403 -0.00414938 0.999947 0.00817118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 8.27031e-05 0.0191383 4.00029 0.0169094 0.000430128 +EDGE_SE3:QUAT 599 755 1.60629 -0.969479 0.0105874 -0.00386167 -0.00458705 0.99995 0.00801343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.23125e-05 0.0154485 4.00015 0.0185941 0.000402964 +EDGE_SE3:QUAT 600 755 -2.62617 -0.896831 0.00311295 -0.00272141 -0.00579808 0.999945 0.0083305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.22884e-05 0.0108873 3.99998 0.0233702 0.000443774 +EDGE_SE3:QUAT 601 755 -6.60172 -0.936505 -0.0484415 0.00371158 0.0063432 -0.999971 0.00218487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.41578e-05 0.0148472 4.00006 0.0253091 0.000234336 +EDGE_SE3:QUAT 686 755 3.02645 -1.37185 -0.00614248 -0.00233097 0.00552158 0.00511898 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -4.7959e-05 0.0443185 3.99988 0.000111875 4.00039 +EDGE_SE3:QUAT 687 755 -0.926375 -1.27073 0.00883602 -0.00103609 0.00442407 0.0082101 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -1.45342e-05 0.0354934 3.99992 0.000145378 4.00005 +EDGE_SE3:QUAT 688 755 -4.95914 -1.16449 -0.0944071 -0.000810493 -0.00245881 0.00780431 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 9.05559e-06 -0.0195932 3.99998 -7.64763e-05 3.99985 +EDGE_SE3:QUAT 756 757 4.27491 -0.0779388 0.0391737 -0.00248578 -0.00474311 0.00310508 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 4.86914e-05 -0.0378543 3.99991 -6.0073e-05 4.00032 +EDGE_SE3:QUAT 480 756 5.70635 1.11965 0.0691465 -0.011635 -0.00580439 0.999861 0.0104766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 0.000301375 0.0465475 4.002 0.0242038 0.00112719 +EDGE_SE3:QUAT 481 756 1.67913 1.23389 0.0277476 -0.00589841 -0.00763425 0.999938 0.00555114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000182143 0.0235964 4.00031 0.0308015 0.000499623 +EDGE_SE3:QUAT 482 756 -2.63492 1.30523 0.0609637 0.00281528 0.00934228 -0.999949 0.0025027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000106459 0.0112627 3.99978 0.0373122 0.000404832 +EDGE_SE3:QUAT 483 756 -6.91621 1.38798 -0.0266569 0.00758829 0.00767383 -0.999927 0.00548922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000227976 0.0303562 4.0007 0.0303686 0.000581425 +EDGE_SE3:QUAT 597 756 5.85802 -1.03383 0.0631666 -0.0110075 -0.0023257 0.999912 0.00696942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 0.000122468 0.0440312 4.00191 0.00992205 0.000703654 +EDGE_SE3:QUAT 598 756 1.79205 -0.912728 0.0258345 -0.00613461 -0.0041085 0.999965 0.00393092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000103861 0.0245392 4.00053 0.0166296 0.000281482 +EDGE_SE3:QUAT 599 756 -2.67166 -0.819156 0.032049 -0.00529696 -0.00467665 0.999967 0.00401642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000101099 0.0211888 4.00036 0.0188787 0.000265862 +EDGE_SE3:QUAT 600 756 -6.90843 -0.736154 0.0255356 -0.00430559 -0.00613214 0.999962 0.00451987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000106246 0.0172237 4.00014 0.024685 0.000308213 +EDGE_SE3:QUAT 686 756 7.33281 -1.4167 -0.00599968 -0.00241667 0.00719873 0.00883592 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00081 -5.89734e-05 0.0578495 3.99979 0.000253056 4.00052 +EDGE_SE3:QUAT 687 756 3.3717 -1.29269 0.018971 -0.00131076 0.00574967 0.0123558 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 -2.04538e-05 0.0461864 3.99987 0.000284765 3.99992 +EDGE_SE3:QUAT 688 756 -0.650587 -1.1861 -0.0215623 -0.000834983 -0.001061 0.0120077 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.79296e-06 -0.00836591 4 -5.00059e-05 3.99944 +EDGE_SE3:QUAT 689 756 -5.16729 -1.05399 -0.0652228 -0.000146397 0.000488436 0.00829397 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.39648e-07 0.00392166 4 1.62819e-05 3.99973 +EDGE_SE3:QUAT 757 758 4.26512 -0.0842164 -0.00658311 0.000415787 -0.00358595 0.00282072 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -5.09762e-06 -0.0287026 3.99995 -4.03646e-05 4.00017 +EDGE_SE3:QUAT 479 757 5.56618 1.25343 0.0579638 -0.00762992 -0.0075678 0.99994 0.00221345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000233188 0.0305217 4.0007 0.0304147 0.000483703 +EDGE_SE3:QUAT 480 757 1.46169 1.29152 0.00794792 -0.00710587 -0.00854593 0.999909 0.00766523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000247619 0.0284285 4.00049 0.0346226 0.00073672 +EDGE_SE3:QUAT 481 757 -2.58539 1.36941 0.0135492 -0.00131847 -0.0102465 0.999943 0.00273295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.1841e-05 0.00527473 3.99961 0.0410124 0.000457379 +EDGE_SE3:QUAT 482 757 -6.91512 1.36996 0.0745137 -0.0018484 0.0119267 -0.99991 0.00581463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.19729e-05 -0.00739544 3.99948 0.047786 0.000719879 +EDGE_SE3:QUAT 596 757 5.77045 -0.981007 0.0558411 -0.00732459 -0.00551376 0.999952 0.0035907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000165372 0.0292996 4.00073 0.0222709 0.000390167 +EDGE_SE3:QUAT 597 757 1.62331 -0.891648 0.0073026 -0.00631749 -0.00497574 0.999959 0.00408969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000128874 0.0252711 4.00053 0.0201129 0.00032768 +EDGE_SE3:QUAT 598 757 -2.46369 -0.799909 0.00895848 -0.00132801 -0.00676458 0.999975 0.00139737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.54779e-05 0.00531243 3.99984 0.0270727 0.000198105 +EDGE_SE3:QUAT 599 757 -6.91495 -0.707172 0.0284248 -0.000830783 -0.00706718 0.999974 0.00145549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.29248e-05 0.00332339 3.99981 0.0282777 0.000211151 +EDGE_SE3:QUAT 688 757 3.59951 -1.16033 0.0260035 -0.00327838 -0.00594495 0.0147482 0.999868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 8.89631e-05 -0.0469688 3.99986 -0.00034774 3.99968 +EDGE_SE3:QUAT 689 757 -0.90773 -1.072 -0.0309809 -0.00268565 -0.00413901 0.0114286 0.999923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 4.84196e-05 -0.0327389 3.99993 -0.000187484 3.99975 +EDGE_SE3:QUAT 690 757 -5.38438 -0.941563 -0.0105957 6.68122e-05 0.000377783 0.00791164 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.27675e-07 0.00301564 4 1.19208e-05 3.99975 +EDGE_SE3:QUAT 758 759 4.18394 -0.0753331 -0.00729732 -0.00130745 0.0133396 0.00225724 0.999908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00284 -6.03141e-05 0.106818 3.99929 0.000115204 4.00283 +EDGE_SE3:QUAT 478 758 5.72318 1.34769 -0.0384917 -0.00877967 0.0058368 -0.999856 0.0133034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000225587 -0.0351287 4.00106 0.0242808 0.00116386 +EDGE_SE3:QUAT 479 758 1.31327 1.36865 -0.0171942 0.00378399 0.00755663 -0.999964 0.000794927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000114476 0.0151372 4 0.0302039 0.000287875 +EDGE_SE3:QUAT 480 758 -2.80224 1.43873 -0.0516226 -0.00344793 -0.00819568 0.99995 0.00457313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000111845 0.0137934 3.99992 0.0329081 0.000401962 +EDGE_SE3:QUAT 481 758 -6.82866 1.4721 0.00284478 0.00241253 -0.0100163 0.999947 0.000325505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.68624e-05 -0.00965154 3.99969 0.0400581 0.000424901 +EDGE_SE3:QUAT 595 758 5.68865 -0.915554 -0.0535955 -0.00962506 0.00488279 -0.999934 0.00389382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 -0.000196094 -0.0385008 4.00138 0.0198401 0.000529621 +EDGE_SE3:QUAT 596 758 1.51014 -0.860493 -0.0130157 -0.00361426 -0.00505173 0.99998 0.000693063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.31178e-05 0.0144575 4.00011 0.0202281 0.000156466 +EDGE_SE3:QUAT 597 758 -2.6598 -0.769599 -0.0473352 -0.002639 -0.00460394 0.999985 0.00113918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.8598e-05 0.0105563 4.00003 0.0184403 0.000118059 +EDGE_SE3:QUAT 598 758 -6.7468 -0.704151 -0.01009 -0.00219124 0.00646665 -0.999976 0.00146718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.63553e-05 -0.00876553 3.99991 0.0258923 0.000195425 +EDGE_SE3:QUAT 689 758 3.38265 -1.05786 -0.00147979 -0.00220981 -0.00790718 0.0146342 0.999859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00097 9.10997e-05 -0.0628621 3.99975 -0.000462556 4.00013 +EDGE_SE3:QUAT 690 758 -1.11097 -0.97556 -0.0191809 0.000450547 -0.00328445 0.0110012 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -3.07873e-06 -0.0263313 3.99996 -0.000144837 3.99969 +EDGE_SE3:QUAT 691 758 -5.54371 -0.83733 -0.0188902 -0.000866499 -0.00612318 0.00672512 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 2.72303e-05 -0.0489185 3.99985 -0.000165252 4.00042 +EDGE_SE3:QUAT 759 760 4.07269 -0.121313 0.0382557 0.0027934 0.00531728 -0.00210267 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 5.8136e-05 0.0426122 3.99989 -4.29369e-05 4.00044 +EDGE_SE3:QUAT 477 759 5.886 1.31427 -0.00637001 -0.000614909 0.00886165 -0.999562 0.0282382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.09521e-06 -0.00246111 3.99969 0.0355134 0.00350668 +EDGE_SE3:QUAT 478 759 1.56839 1.31839 0.0253544 0.00457264 0.0072432 -0.999842 0.0155637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000130716 0.0182986 4.00015 0.0283888 0.00125416 +EDGE_SE3:QUAT 479 759 -2.85598 1.43723 -0.0515604 0.0171978 0.00842189 -0.999813 0.0028101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99881 0.000563231 0.0687886 4.00447 0.0333534 0.00149256 +EDGE_SE3:QUAT 480 759 -6.964 1.56739 -0.09252 -0.0169266 -0.00935905 0.999809 0.00266179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99886 0.000652473 0.0677067 4.00422 0.0378539 0.00153237 +EDGE_SE3:QUAT 594 759 5.8237 -0.944062 -0.015218 -0.000262426 0.00923456 -0.999908 0.00997416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.89174e-06 -0.00104986 3.99966 0.0369484 0.000739571 +EDGE_SE3:QUAT 595 759 1.54693 -0.870542 0.0185387 0.00368949 0.00612595 -0.999958 0.00572389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.02186e-05 0.0147594 4.00007 0.0243343 0.000333552 +EDGE_SE3:QUAT 596 759 -2.64236 -0.776474 -0.0482918 0.0167574 0.00609941 -0.99984 0.00131307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99887 0.000401942 0.0670241 4.00435 0.0242585 0.00127715 +EDGE_SE3:QUAT 597 759 -6.82577 -0.680145 -0.084251 0.0160536 0.00578266 -0.999854 0.00100384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99897 0.000366695 0.0642095 4.004 0.0230339 0.00116745 +EDGE_SE3:QUAT 690 759 3.05279 -0.945735 0.000181276 -0.000983127 0.00990356 0.0129297 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 -8.55452e-06 0.0793884 3.99961 0.000511727 4.00091 +EDGE_SE3:QUAT 691 759 -1.37616 -0.852634 0.0319257 -0.00207488 0.00730398 0.00879801 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 -4.96267e-05 0.0586548 3.99978 0.000255806 4.00055 +EDGE_SE3:QUAT 692 759 -5.79768 -0.71409 -0.00553617 -0.00480781 0.00272092 0.00428476 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.23454e-05 0.0220138 3.99997 4.64717e-05 4.00005 +EDGE_SE3:QUAT 760 761 4.34625 -0.117541 0.0547725 0.0017266 -0.00555845 -0.00495321 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 -4.19452e-05 -0.0443679 3.99988 0.000111107 4.00039 +EDGE_SE3:QUAT 476 760 6.29911 1.21574 0.0442488 0.00935903 0.00899929 -0.99915 0.0391268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000272203 0.0375275 4.00123 0.0329501 0.00674806 +EDGE_SE3:QUAT 477 760 1.82815 1.21441 0.0342098 0.00471992 0.00619054 -0.999626 0.0262321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000109631 0.0189007 4.00024 0.0237324 0.00298277 +EDGE_SE3:QUAT 478 760 -2.51158 1.31874 0.0250961 0.00984222 0.0044806 -0.999847 0.0137331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000146375 0.039379 4.0015 0.0168416 0.00121307 +EDGE_SE3:QUAT 479 760 -6.89024 1.53655 -0.148019 0.0224877 0.00538523 -0.999732 0.000916868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99798 0.000476869 0.0899321 4.00799 0.0214351 0.00214086 +EDGE_SE3:QUAT 593 760 6.01814 -0.971026 0.0491103 0.0108966 0.00737453 -0.99984 0.0121545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000291827 0.0435966 4.00173 0.0284458 0.00126842 +EDGE_SE3:QUAT 594 760 1.77617 -0.902638 0.024717 0.00491008 0.00649235 -0.999936 0.007838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000125528 0.0196431 4.00023 0.0256605 0.000506817 +EDGE_SE3:QUAT 595 760 -2.5128 -0.801793 0.0246052 0.00884507 0.00332342 -0.999948 0.00390528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000110692 0.0353802 4.00121 0.0130223 0.000416351 +EDGE_SE3:QUAT 596 760 -6.69802 -0.669476 -0.149585 -0.0222181 -0.00348935 0.999747 0.000833111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99803 0.000322055 0.0888522 4.00786 0.0141439 0.00202729 +EDGE_SE3:QUAT 690 760 7.11235 -0.972911 -0.0477187 0.00194374 0.0153282 0.0109641 0.999821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00373 0.000180886 0.122447 3.99907 0.00068334 4.00326 +EDGE_SE3:QUAT 691 760 2.69005 -0.896261 0.0116977 0.00100549 0.0124534 0.00682644 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00247 7.55288e-05 0.099592 3.99938 0.000344121 4.00229 +EDGE_SE3:QUAT 692 760 -1.75446 -0.799079 0.0129496 -0.0016759 0.00771705 0.00223701 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 -4.8623e-05 0.0617936 3.99976 6.67774e-05 4.00093 +EDGE_SE3:QUAT 693 760 -6.16181 -0.649624 -0.0793957 -0.00376082 0.00234209 -0.00202189 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.52696e-05 0.0186453 3.99998 -1.93109e-05 4.00007 +EDGE_SE3:QUAT 761 762 4.2836 -0.130879 0.0117282 0.000638452 -0.00566731 -0.00726642 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -2.00454e-05 -0.0452843 3.99987 0.000165002 4.0003 +EDGE_SE3:QUAT 475 761 6.43593 0.978455 0.0790399 0.00970901 0.00701536 -0.99888 0.0457778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99958 0.000178351 0.0389626 4.00145 0.0243789 0.0089117 +EDGE_SE3:QUAT 476 761 1.95506 0.990159 0.0160025 0.00392992 0.00698755 -0.999378 0.034352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000108431 0.0157506 4.0001 0.026791 0.004962 +EDGE_SE3:QUAT 477 761 -2.48297 1.11036 0.0443438 -0.000715108 0.00427582 -0.999762 0.0213918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.28078e-06 -0.00286213 3.99993 0.0172059 0.00190653 +EDGE_SE3:QUAT 478 761 -6.81932 1.31898 -0.00172712 0.0041124 0.00278121 -0.99995 0.00869247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.27148e-05 0.0164515 4.00024 0.0108378 0.000399269 +EDGE_SE3:QUAT 592 761 6.16997 -1.0261 0.0524643 0.00848256 0.0097669 -0.99985 0.0115432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000319846 0.0339403 4.00082 0.0382852 0.00118739 +EDGE_SE3:QUAT 593 761 1.68125 -0.958438 0.00797685 0.00518974 0.00549514 -0.999944 0.00744459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000110995 0.0207613 4.00032 0.0216714 0.000446857 +EDGE_SE3:QUAT 594 761 -2.56879 -0.853423 0.0302114 -0.000663668 0.00503289 -0.999983 0.00280302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.282e-05 -0.0026548 3.99991 0.0201458 0.000134656 +EDGE_SE3:QUAT 595 761 -6.85767 -0.713352 0.00543805 -0.00333675 -0.00153504 0.999992 0.00126618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.08053e-05 0.013347 4.00017 0.00617433 6.04792e-05 +EDGE_SE3:QUAT 691 761 7.00428 -0.960509 -0.0483872 0.00245845 0.00703159 0.00169479 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 7.11205e-05 0.0562117 3.9998 5.05576e-05 4.00078 +EDGE_SE3:QUAT 692 761 2.58298 -0.88911 -0.00326668 9.15288e-06 0.00202622 -0.00281524 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -2.03217e-07 0.0162101 3.99998 -2.28178e-05 4.00003 +EDGE_SE3:QUAT 693 761 -1.81895 -0.788673 -0.0447478 -0.00191286 -0.00317842 -0.00712577 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 2.2784e-05 -0.0255898 3.99996 9.09066e-05 3.99996 +EDGE_SE3:QUAT 694 761 -6.19768 -0.646769 -0.0141534 -0.00224769 0.00298801 -0.0112133 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.87627e-05 0.0235976 3.99997 -0.000132214 3.99964 +EDGE_SE3:QUAT 762 763 4.28395 -0.137984 -0.00357486 0.00121568 -0.00444651 -0.00724447 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -2.49619e-05 -0.035466 3.99992 0.000128936 4.0001 +EDGE_SE3:QUAT 474 762 6.7044 0.640607 0.0854725 0.00940468 0.00841887 -0.999013 0.0425932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000241741 0.0377267 4.00129 0.0303388 0.00784374 +EDGE_SE3:QUAT 475 762 2.16261 0.720613 0.00661339 0.00372287 0.00602899 -0.999236 0.0384391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.60281e-05 0.0149278 4.00012 0.0228854 0.0060972 +EDGE_SE3:QUAT 476 762 -2.29482 0.840227 -0.00851216 -0.0016948 0.00605551 -0.999616 0.0269882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.45384e-05 -0.00678599 3.99989 0.0245434 0.00307567 +EDGE_SE3:QUAT 477 762 -6.80913 1.05583 0.0597043 -0.00618265 0.00330736 -0.999875 0.0142047 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -9.33563e-05 -0.0247381 4.00055 0.013928 0.00100862 +EDGE_SE3:QUAT 591 762 6.24871 -1.06558 0.0648283 0.00944524 0.00909504 -0.99989 0.00695154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000333449 0.0377864 4.00113 0.0358669 0.000871776 +EDGE_SE3:QUAT 592 762 1.90326 -0.996612 -0.00815044 0.00261989 0.00889274 -0.999949 0.00405473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.50594e-05 0.0104811 3.9998 0.0354845 0.000408031 +EDGE_SE3:QUAT 593 762 -2.57426 -0.889154 -0.0275723 -0.000577396 0.00477281 -0.999988 3.85714e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.1016e-05 -0.00230966 3.99991 0.0190912 9.24604e-05 +EDGE_SE3:QUAT 594 762 -6.85686 -0.738702 0.0448112 0.00628671 -0.00409193 0.999963 0.00421683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -9.94883e-05 -0.0251476 4.00057 0.0161583 0.000294496 +EDGE_SE3:QUAT 692 762 6.88477 -1.04603 -0.0089641 0.000889356 -0.00364179 -0.00992606 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -1.60337e-05 -0.0290254 3.99995 0.000144173 3.99982 +EDGE_SE3:QUAT 693 762 2.44605 -0.97898 -0.0104464 -0.00103886 -0.00918845 -0.0145867 0.999851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00135 8.66604e-06 -0.0736877 3.99966 0.000536179 4.00051 +EDGE_SE3:QUAT 694 762 -1.9698 -0.874708 -0.0327443 -0.00155106 -0.00293475 -0.018894 0.999816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.4566e-05 -0.0238177 3.99996 0.000225765 3.99871 +EDGE_SE3:QUAT 695 762 -6.22044 -0.718948 -0.0171884 -7.24566e-05 0.00195271 -0.0252891 0.999678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.87076e-06 0.0155849 3.99998 -0.000196923 3.9975 +EDGE_SE3:QUAT 763 764 4.28321 -0.113379 0.0149811 -0.00260179 0.00528743 -0.00538271 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -5.83425e-05 0.0421332 3.99989 -0.000115011 4.00033 +EDGE_SE3:QUAT 473 763 6.87053 0.279097 0.0024861 0.000534433 0.00386128 -0.999489 0.0317383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.16726e-05 0.002142 3.99995 0.0152706 0.00408878 +EDGE_SE3:QUAT 474 763 2.43576 0.414638 0.000857953 0.00486705 0.00702475 -0.999335 0.0354526 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.00012786 0.0195083 4.00024 0.0266353 0.00530041 +EDGE_SE3:QUAT 475 763 -2.08782 0.536569 -0.0306497 -0.000572074 0.00474811 -0.999492 0.0315137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.28095e-06 -0.00229057 3.99991 0.0190892 0.00406497 +EDGE_SE3:QUAT 476 763 -6.56518 0.743835 0.00901233 -0.00598419 0.00460984 -0.999766 0.0202765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -0.000123641 -0.0239517 4.00046 0.0193942 0.00188208 +EDGE_SE3:QUAT 590 763 5.92862 -1.08119 -0.0279455 -0.00233942 0.00456975 -0.999987 0.000770638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.27358e-05 -0.00935796 4 0.0182937 0.000107933 +EDGE_SE3:QUAT 591 763 1.91944 -0.999539 -0.0106817 0.00479956 0.00772811 -0.999959 2.07664e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000148395 0.0191998 4.00013 0.0309146 0.000331071 +EDGE_SE3:QUAT 592 763 -2.35497 -0.897078 -0.0225669 0.00196367 -0.00753916 0.999965 0.00302619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.03015e-05 -0.00785544 3.99984 0.0301082 0.000278694 +EDGE_SE3:QUAT 593 763 -6.84845 -0.751117 -0.0220272 0.00482203 -0.00351744 0.999954 0.007478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -6.4372e-05 -0.0192899 4.00033 0.013781 0.00036419 +EDGE_SE3:QUAT 693 763 6.73914 -1.24036 0.0665917 0.000395644 -0.0136275 -0.0213909 0.999678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00296 -0.000116782 -0.108914 3.99926 0.00116828 4.00113 +EDGE_SE3:QUAT 694 763 2.28114 -1.16673 -0.00763391 -0.000295082 -0.00730749 -0.0259375 0.999637 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00086 -2.46518e-05 -0.0585037 3.99979 0.000758909 3.99816 +EDGE_SE3:QUAT 695 763 -1.93708 -1.07175 -0.0307471 0.00126217 -0.00243571 -0.0324746 0.999469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.62939e-05 -0.0189637 3.99998 0.00030528 3.99587 +EDGE_SE3:QUAT 696 763 -6.49032 -0.768549 0.0364352 0.000970887 0.00284243 -0.0565634 0.998394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -6.98125e-09 0.0232887 3.99997 -0.000663686 3.98734 +EDGE_SE3:QUAT 764 765 4.11395 -0.0937928 0.0485709 -0.00414164 -0.00440418 -0.00174132 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 7.24042e-05 -0.0353213 3.99992 2.88484e-05 4.0003 +EDGE_SE3:QUAT 472 764 6.86935 -0.157617 0.00641742 0.00610751 0.00520758 -0.999928 0.00896263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.00012104 0.0244335 4.0005 0.0203922 0.00057453 +EDGE_SE3:QUAT 473 764 2.61377 0.129292 0.0125752 0.00552852 0.00668947 -0.999633 0.0256798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000136779 0.0221377 4.00036 0.0255828 0.00292413 +EDGE_SE3:QUAT 474 764 -1.83703 0.227891 -0.0260459 0.0100981 0.00991185 -0.999444 0.0301985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 0.000344912 0.0404519 4.00138 0.0371399 0.00440233 +EDGE_SE3:QUAT 475 764 -6.31936 0.391055 -0.0193343 0.00470019 0.00778635 -0.999624 0.0258699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000143668 0.018822 4.00016 0.0301244 0.00299265 +EDGE_SE3:QUAT 589 764 5.71508 -1.21616 0.0247375 -0.00919158 -0.00431763 0.999701 0.0222522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000199444 0.0367932 4.00123 0.0188932 0.00240851 +EDGE_SE3:QUAT 590 764 1.64281 -0.975901 0.010409 -0.00262097 -0.00732849 0.999959 0.00469218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.55604e-05 0.010485 3.99989 0.029411 0.000331811 +EDGE_SE3:QUAT 591 764 -2.32359 -0.871913 -0.0426764 -0.0102798 -0.0106149 0.999875 0.00563659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000446004 0.0411261 4.00121 0.0429419 0.00101076 +EDGE_SE3:QUAT 592 764 -6.63183 -0.74996 0.00216006 -0.00349259 -0.0104008 0.999902 0.00865521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000140166 0.0139741 3.99975 0.0418377 0.000786122 +EDGE_SE3:QUAT 694 764 6.56802 -1.50459 0.0688793 -0.0026818 -0.00173084 -0.0315852 0.999496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.7814e-05 -0.0148418 3.99999 0.000239425 3.99606 +EDGE_SE3:QUAT 695 764 2.33979 -1.4662 0.00509424 -0.00105683 0.00263165 -0.0378425 0.99928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -1.6809e-05 0.020529 3.99997 -0.000385317 3.99438 +EDGE_SE3:QUAT 696 764 -2.23368 -1.37086 0.028715 -0.00109055 0.00847173 -0.0619385 0.998043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -0.000140125 0.0665915 3.99973 -0.00205324 3.98576 +EDGE_SE3:QUAT 697 764 -6.54017 -0.850537 -0.0153084 0.00218213 0.00545864 -0.103718 0.994589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -2.94093e-05 0.0456679 3.99987 -0.00240207 3.95749 +EDGE_SE3:QUAT 765 766 4.03125 -0.0701928 0.0281049 0.00175453 0.00415772 0.0201351 0.999787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 3.68498e-05 0.0328194 3.99993 0.000329692 3.99865 +EDGE_SE3:QUAT 471 765 7.01846 -1.06036 -0.11659 0.00806503 -0.00776534 0.997452 0.0704601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 -0.000155172 -0.032521 4.001 0.0261627 0.0202965 +EDGE_SE3:QUAT 472 765 2.73769 -0.128656 0.00404622 0.00168693 0.00921661 -0.99993 0.00725709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.65658e-05 0.00674916 3.99971 0.0367627 0.000559965 +EDGE_SE3:QUAT 473 765 -1.50258 0.00338061 0.0140013 0.000990824 0.0105832 -0.999651 0.0241658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.25709e-05 0.00396883 3.99958 0.0420775 0.00278281 +EDGE_SE3:QUAT 474 765 -5.95562 0.076009 -0.0596948 0.00534328 0.013825 -0.999491 0.0282578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000315471 0.0214068 3.9998 0.0539878 0.00403795 +EDGE_SE3:QUAT 588 765 5.86489 -1.76342 -0.0390307 -0.00026687 -0.0094793 0.993188 0.116136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.02873e-05 0.000969467 3.99967 0.0368879 0.0542959 +EDGE_SE3:QUAT 589 765 1.60197 -0.927787 -0.00644665 -0.00464478 -0.00864916 0.99966 0.024164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000157284 0.0185964 4 0.0354459 0.00273636 +EDGE_SE3:QUAT 590 765 -2.4836 -0.821114 0.0375086 0.00178519 -0.0113163 0.999914 0.00643686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.68372e-05 -0.00714264 3.99955 0.0451665 0.000688566 +EDGE_SE3:QUAT 591 765 -6.35801 -0.722429 -0.0754311 -0.00579966 -0.0150393 0.999844 0.0072895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000341286 0.023208 3.9996 0.060491 0.00126208 +EDGE_SE3:QUAT 695 765 6.46218 -1.87087 0.0252104 -0.00530551 -0.00172734 -0.0395234 0.999203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 4.17587e-05 -0.0162997 3.99998 0.000337986 3.99382 +EDGE_SE3:QUAT 696 765 1.85295 -1.96235 0.00223198 -0.00541938 0.00432817 -0.0635256 0.997956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -0.000101497 0.0302957 3.99995 -0.000918446 3.98409 +EDGE_SE3:QUAT 697 765 -2.53007 -1.79401 -0.0165887 -0.00218944 0.00150427 -0.105874 0.994376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.26136e-05 0.00907149 4 -0.00042762 3.95518 +EDGE_SE3:QUAT 698 765 -6.88439 -0.922126 -0.187854 -0.00429198 -0.0121037 -0.181888 0.983235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00249 -0.000476856 -0.101283 3.99943 0.00934465 3.87023 +EDGE_SE3:QUAT 766 767 4.09067 0.215492 -0.01341 0.00281674 0.00894915 0.106646 0.994253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00108 0.000277142 0.0668125 3.99975 0.00348434 3.95562 +EDGE_SE3:QUAT 470 766 6.61538 -2.46062 -0.0617023 0.00715271 -0.0124602 0.971342 0.23725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -1.40021e-05 -0.0322496 4.00124 0.0301682 0.225685 +EDGE_SE3:QUAT 471 766 3.0213 -0.429314 -0.0126476 0.00378181 -0.00583977 0.998704 0.0504267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -8.11432e-05 -0.0151913 4.00015 0.0216906 0.0103472 +EDGE_SE3:QUAT 472 766 -1.30544 -0.118745 0.021285 0.00609702 0.00735714 -0.999581 0.0273369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000164808 0.0244177 4.00044 0.0280466 0.00333518 +EDGE_SE3:QUAT 473 766 -5.54981 -0.123149 0.0359336 0.00546197 0.00903807 -0.998965 0.0442459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000188456 0.02192 4.00026 0.0340511 0.00824162 +EDGE_SE3:QUAT 587 766 5.69193 -2.00586 -0.0630158 0.00783624 -0.0112736 0.971753 0.235601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 7.39959e-05 -0.0350188 4.00143 0.025021 0.222537 +EDGE_SE3:QUAT 588 766 1.95192 -0.775164 -0.000458898 -0.00430488 -0.00731661 0.99535 0.0959524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000110162 0.0174055 3.99995 0.0318701 0.0371598 +EDGE_SE3:QUAT 589 766 -2.42509 -0.667508 -0.0135457 -0.00918533 -0.00667501 0.999928 0.00398958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.00025211 0.0367433 4.00116 0.027004 0.00058344 +EDGE_SE3:QUAT 590 766 -6.51765 -0.705324 0.0803425 0.00251725 0.00987115 -0.999853 0.0138113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000107738 0.0100736 3.99973 0.0391873 0.00117239 +EDGE_SE3:QUAT 696 766 5.85754 -2.55446 -0.000590637 -0.00320902 0.0084692 -0.0435088 0.999012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00104 -0.000176631 0.0659023 3.99974 -0.00142645 3.99351 +EDGE_SE3:QUAT 697 766 1.40871 -2.72313 0.00190827 0.000219748 0.00550425 -0.08611 0.99627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 -5.74696e-05 0.0437756 3.99988 -0.00188139 3.97082 +EDGE_SE3:QUAT 698 766 -3.14958 -2.43875 -0.0607271 -0.0020941 -0.00843955 -0.162175 0.986724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00117 -0.000217243 -0.0688923 3.99973 0.00562368 3.89598 +EDGE_SE3:QUAT 767 768 4.24867 0.650931 0.0185345 0.00117994 -0.00451328 0.19059 0.981659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 7.58879e-05 -0.0367929 3.99993 -0.00352783 3.85504 +EDGE_SE3:QUAT 469 767 6.06086 -3.3535 -0.0096513 -0.00475717 -0.0108019 0.917411 0.397766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000201154 0.0175428 3.99953 0.0398367 0.633432 +EDGE_SE3:QUAT 470 767 2.88221 -0.753451 0.00455784 -0.00236 -0.00818944 0.991126 0.132649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.50287e-06 0.00953336 3.99973 0.0337849 0.070696 +EDGE_SE3:QUAT 471 767 -1.07387 -0.208798 -0.00368447 0.00577945 0.00267328 -0.998388 0.0564041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 1.69133e-05 0.0232313 4.00054 0.00800997 0.0128772 +EDGE_SE3:QUAT 472 767 -5.38766 -0.548524 -0.0499579 0.0161457 0.00384149 -0.990848 0.133956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99898 -0.000618159 0.066363 4.00429 -0.00232187 0.0728992 +EDGE_SE3:QUAT 586 767 5.72575 -1.73189 0.019674 -0.00496223 -0.00847267 0.952774 0.303521 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.18752e-05 0.0205028 3.99968 0.0372792 0.368987 +EDGE_SE3:QUAT 587 767 1.94224 -0.30443 0.00422379 -0.00150088 -0.00723962 0.991396 0.130689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.19851e-05 0.00602615 3.99979 0.029271 0.0685453 +EDGE_SE3:QUAT 588 767 -2.11684 -0.183976 -0.0492129 0.0137889 0.00287827 -0.999846 0.0105129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99923 0.000111585 0.0551597 4.00303 0.0103609 0.00122977 +EDGE_SE3:QUAT 589 767 -6.53788 -0.839322 -0.104531 0.0188601 0.00256696 -0.994545 0.102554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99862 -0.000692672 0.0766312 4.00573 -0.00533091 0.04356 +EDGE_SE3:QUAT 697 767 5.48395 -3.21436 -0.0626309 0.00460769 0.0142013 0.0207332 0.999674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00307 0.000357501 0.112465 3.99922 0.00118605 4.00144 +EDGE_SE3:QUAT 698 767 0.803482 -3.56128 -0.00572796 0.00154722 0.000453285 -0.0561262 0.998422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.44887e-06 0.00464904 4 -0.000140043 3.9874 +EDGE_SE3:QUAT 699 767 -3.88432 -3.11562 0.0283696 -0.00211436 0.00479147 -0.147049 0.989115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -9.99006e-05 0.0334196 3.99994 -0.00233624 3.91378 +EDGE_SE3:QUAT 768 769 4.0962 0.64137 0.0161729 -0.00116505 -0.00169333 0.192507 0.981294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.39962e-05 -0.0101758 4 -0.000868402 3.85179 +EDGE_SE3:QUAT 468 768 5.86182 -3.0976 -0.0256236 -0.000761933 -0.00341379 0.880879 0.473329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.84983e-05 0.000991507 3.99999 0.00887757 0.896193 +EDGE_SE3:QUAT 469 768 2.67142 -0.685398 -0.00825596 -0.00221103 -0.0103131 0.976451 0.215481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.6043e-05 0.00861226 3.99958 0.0401744 0.186172 +EDGE_SE3:QUAT 470 768 -1.39951 -0.257502 -0.000711605 -0.000612145 0.00705928 -0.998236 0.0589393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.27706e-06 -0.00244976 3.9998 0.0282791 0.0140975 +EDGE_SE3:QUAT 471 768 -5.23529 -1.34928 -0.0359896 0.00200789 0.000351025 -0.969215 0.246208 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.07947e-05 0.00876998 4.00006 -0.00251931 0.242495 +EDGE_SE3:QUAT 585 768 5.76456 -1.16356 0.024174 -0.00498515 -0.00354319 0.958185 0.286084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000112849 0.0215724 4.00008 0.0218341 0.327624 +EDGE_SE3:QUAT 586 768 1.87273 0.199122 0.00454475 -0.00204164 -0.00768718 0.993209 0.116071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.18332e-06 0.00823408 3.99977 0.0315873 0.0541602 +EDGE_SE3:QUAT 587 768 -2.34045 0.173797 0.00796183 -0.00152016 0.00621278 -0.998109 0.0611348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.03312e-05 -0.00610352 3.99986 0.0253596 0.0151205 +EDGE_SE3:QUAT 588 768 -6.35373 -0.915625 -0.150826 0.00979792 -0.000656882 -0.979541 0.201003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000438617 0.0414534 4.0013 -0.0174948 0.16213 +EDGE_SE3:QUAT 654 768 5.20397 -4.4723 -0.0297958 -0.000655693 -0.00032967 0.871741 0.489966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.32255e-06 0.00307393 4 0.00255075 0.960272 +EDGE_SE3:QUAT 655 768 1.19279 -4.37987 -0.0537888 -0.00146591 -0.00188104 0.871911 0.489659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.65312e-06 0.00579753 3.99998 0.00777999 0.959094 +EDGE_SE3:QUAT 656 768 -3.17468 -4.31353 -0.0782388 0.000479693 -0.000861639 0.877411 0.479738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.44634e-06 -0.00321957 4.00001 0.000214771 0.920599 +EDGE_SE3:QUAT 698 768 5.10784 -3.3882 0.00984971 0.00243418 -0.00421257 0.135292 0.990794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 2.05778e-05 -0.0366858 3.99992 -0.0025489 3.92712 +EDGE_SE3:QUAT 699 768 0.378717 -3.73119 0.0023897 -0.000349589 0.000393223 0.0441362 0.999025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.12332e-07 0.00332151 4 7.45925e-05 3.99221 +EDGE_SE3:QUAT 700 768 -5.00045 -2.92794 0.00504551 -0.000457711 0.00231218 -0.0885885 0.996066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.47666e-05 0.0177964 3.99998 -0.000777958 3.96869 +EDGE_SE3:QUAT 769 770 4.1528 0.756939 0.00866841 -0.00288631 0.00741504 0.216948 0.976151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 0.000226312 0.0624739 3.99979 0.00689151 3.81271 +EDGE_SE3:QUAT 467 769 6.58366 -2.61596 -0.135 0.0140635 -0.00427264 0.847979 0.529825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 0.00187988 -0.0796173 4.00185 -0.0365661 1.12502 +EDGE_SE3:QUAT 468 769 3.07806 -0.0246936 0.00407437 -8.96611e-05 -0.00581988 0.95544 0.295129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.03084e-05 -0.000794676 3.99994 0.0185611 0.348502 +EDGE_SE3:QUAT 469 769 -1.29484 0.477385 -0.000828102 -0.0026248 -0.0113464 0.999656 0.0235057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.77872e-05 0.0105085 3.99956 0.0458147 0.00276277 +EDGE_SE3:QUAT 470 769 -5.39125 -1.34246 0.00928113 -0.000883349 0.00803325 -0.968192 0.250079 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.78196e-05 -0.00284336 3.9998 0.0288766 0.250385 +EDGE_SE3:QUAT 515 769 5.1298 4.07508 0.0436368 0.0041737 -0.0018502 -0.32292 0.946415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.84819e-05 0.00250135 4 -0.00140388 3.58288 +EDGE_SE3:QUAT 516 769 0.781817 4.02722 0.0028177 0.00111184 -0.00064166 -0.341267 0.939966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.61557e-07 -6.34657e-05 4 -0.000301832 3.53415 +EDGE_SE3:QUAT 517 769 -3.66327 4.08698 -0.0344518 0.00699984 -0.00587252 -0.335769 0.9419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -5.55919e-05 -0.0131756 4.00002 0.000162397 3.54904 +EDGE_SE3:QUAT 584 769 6.11696 -0.681018 -0.0177637 0.00318269 -0.00655115 0.969544 0.244807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -1.71132e-05 -0.0145913 4.00026 0.0165039 0.239856 +EDGE_SE3:QUAT 585 769 1.98901 0.560878 0.000826315 -0.00436825 -0.00416786 0.995337 0.0962722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.26556e-05 0.0176852 4.00015 0.019621 0.0372491 +EDGE_SE3:QUAT 586 769 -2.25693 0.541454 0.0105281 0.00207262 0.00866606 -0.996978 0.0771746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000102298 0.00839706 3.99985 0.0328775 0.0241135 +EDGE_SE3:QUAT 587 769 -6.32593 -0.931233 0.0303047 -0.00194391 0.00779371 -0.967737 0.251833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.51485e-05 -0.0074834 3.99976 0.0300101 0.253934 +EDGE_SE3:QUAT 653 769 6.60185 -1.3565 -0.072534 0.00789447 0.000628901 0.950592 0.310343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000376323 -0.0356537 4.00067 -0.0196493 0.38569 +EDGE_SE3:QUAT 654 769 2.52864 -1.28649 -0.0100201 -6.83818e-05 -0.0023477 0.949798 0.312855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.20874e-06 -0.000264481 3.99999 0.00732777 0.391527 +EDGE_SE3:QUAT 655 769 -1.48373 -1.20696 -0.0404513 -0.00112736 -0.00334422 0.949805 0.312823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.45186e-05 0.00430235 3.99995 0.0127639 0.391484 +EDGE_SE3:QUAT 656 769 -5.91904 -1.19229 -0.0517752 0.000959475 -0.00264732 0.953328 0.301923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.35969e-06 -0.00490871 4.00003 0.00614845 0.364648 +EDGE_SE3:QUAT 699 769 4.41537 -2.74922 0.0231592 -0.00156556 -0.0011876 0.235692 0.971826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.87984e-06 -0.0044563 4 -0.000319111 3.7778 +EDGE_SE3:QUAT 700 769 -0.853472 -3.04037 0.0112416 -0.00132575 0.000907578 0.104631 0.99451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.35114e-06 0.00879416 3.99999 0.000486968 3.95623 +EDGE_SE3:QUAT 701 769 -5.98494 -1.92679 -0.164262 0.00573103 -0.0125586 -0.0383146 0.99917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00225 -0.000416444 -0.09766 3.99942 0.0018764 3.99651 +EDGE_SE3:QUAT 770 771 4.21115 0.833802 -0.00505884 0.0010306 0.00453559 0.232977 0.972471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 0.000105608 0.0305952 3.99996 0.00333392 3.78312 +EDGE_SE3:QUAT 467 770 4.09543 0.813659 0.00243189 0.00493428 -0.00604994 0.942708 0.333527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000174832 -0.024541 4.00062 0.00603733 0.445149 +EDGE_SE3:QUAT 468 770 -0.708094 1.70522 0.0266038 -0.00941608 -0.00651642 0.996662 0.0808284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000363489 0.0380077 4.00099 0.0317028 0.0267487 +EDGE_SE3:QUAT 469 770 -5.45489 -0.0350512 -0.0244836 0.0127487 0.013605 -0.980944 0.193396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99899 -0.000168631 0.0545486 4.00329 0.0304418 0.150635 +EDGE_SE3:QUAT 516 770 4.44632 1.92419 0.0139634 0.000930849 0.00708526 -0.129284 0.991582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0008 -0.000130761 0.0567049 3.99981 -0.00366646 3.93395 +EDGE_SE3:QUAT 517 770 0.0474172 2.03091 0.00928212 0.00529953 0.000775781 -0.123668 0.992309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 3.66319e-05 0.0138486 3.99998 -0.00101514 3.93887 +EDGE_SE3:QUAT 518 770 -4.54113 2.07091 -0.0120416 0.00302496 -0.00358573 -0.112622 0.993627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -6.08697e-05 -0.0240885 3.99997 0.00127024 3.94941 +EDGE_SE3:QUAT 583 770 6.20037 0.182873 0.0140899 4.23047e-05 -0.00350131 0.996325 0.0855872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.63786e-06 -0.000188659 3.99995 0.0137206 0.0293481 +EDGE_SE3:QUAT 584 770 2.11596 0.647899 0.0255684 -0.00648276 -0.00840286 0.999535 0.0285922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000227833 0.0259639 4.00032 0.0350305 0.00374571 +EDGE_SE3:QUAT 585 770 -2.16684 0.685513 -0.00991423 0.0129608 0.00578932 -0.992443 0.121887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99926 -0.000217371 0.0530629 4.00288 0.00985772 0.0601658 +EDGE_SE3:QUAT 586 770 -6.19788 -0.769124 -0.013636 0.0110722 0.0112897 -0.956394 0.291652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9993 -0.000662195 0.0517993 4.00278 0.0122133 0.341037 +EDGE_SE3:QUAT 652 770 6.80519 0.442049 0.0184363 0.00042938 -0.00155148 0.995511 0.0946303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.62359e-06 -0.00175096 4 0.00574529 0.0358287 +EDGE_SE3:QUAT 653 770 2.82426 0.498568 0.000514808 -1.1231e-06 -0.00157418 0.995276 0.0970783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.8372e-06 -6.96891e-06 3.99999 0.00614972 0.0377063 +EDGE_SE3:QUAT 654 770 -1.21688 0.591112 0.00529209 -0.00851229 -0.00303236 0.995004 0.0994212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000249994 0.0345274 4.00097 0.0185413 0.0399255 +EDGE_SE3:QUAT 655 770 -5.23612 0.684015 -0.0281396 -0.0100193 -0.00385522 0.994968 0.0996137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000354804 0.0406407 4.00132 0.0229569 0.0402408 +EDGE_SE3:QUAT 700 770 3.11825 -1.40335 0.00674911 -0.00484412 0.00806757 0.317717 0.948139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00121 0.000444243 0.072266 3.99979 0.011896 3.59753 +EDGE_SE3:QUAT 701 770 -1.79215 -1.51581 -0.0497822 0.000430519 -0.00603162 0.1793 0.983776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 0.000141991 -0.0468569 3.99988 -0.00415842 3.87195 +EDGE_SE3:QUAT 702 770 -6.22224 -0.473999 -0.0668628 0.000140651 -0.00562891 0.0626348 0.998021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 4.43146e-05 -0.0448769 3.99988 -0.00140412 3.98481 +EDGE_SE3:QUAT 771 772 4.1744 0.921179 0.00115765 -0.00126813 0.00112784 0.244537 0.969638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.76597e-06 0.0117986 3.99999 0.00155947 3.76084 +EDGE_SE3:QUAT 466 771 5.68195 1.50471 0.0676965 -0.003231 -0.00580244 0.945925 0.324318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.97262e-05 0.0132139 3.99985 0.0248371 0.420946 +EDGE_SE3:QUAT 467 771 0.344458 2.7954 0.0501086 -0.00048855 -0.00457792 0.994499 0.104643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.70061e-06 0.00194405 3.99992 0.0182166 0.0438857 +EDGE_SE3:QUAT 468 771 -4.91749 1.60531 -0.0694316 0.0154843 0.00166745 -0.98794 0.15405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99916 -0.000780773 0.064148 4.00374 -0.0123757 0.0960158 +EDGE_SE3:QUAT 517 771 4.33863 1.78687 0.00505569 0.006851 0.00377445 0.111036 0.993786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 8.09979e-05 0.0205839 3.99998 0.000964823 3.95079 +EDGE_SE3:QUAT 518 771 -0.260813 1.91814 0.0168479 0.0035706 0.000141685 0.122003 0.992523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.00092e-05 -0.00406732 4 -0.000354904 3.94046 +EDGE_SE3:QUAT 519 771 -4.3132 1.963 0.0194432 0.00275331 0.00253174 0.132023 0.99124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.25238e-05 0.0154153 3.99999 0.000910148 3.93034 +EDGE_SE3:QUAT 582 771 6.27017 0.0425351 0.0424296 0.00579768 0.00122601 -0.988829 0.14894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -9.51259e-05 0.0239815 4.00055 -0.00212138 0.0888799 +EDGE_SE3:QUAT 583 771 1.9137 0.102726 0.011382 0.00524851 0.00261908 -0.988852 0.148789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -5.1094e-05 0.0217481 4.00048 0.00379228 0.0886779 +EDGE_SE3:QUAT 584 771 -2.08106 0.083643 -0.0417196 0.0128006 0.00526331 -0.978698 0.20484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99936 -0.000611284 0.0546791 4.00284 -0.00122654 0.168619 +EDGE_SE3:QUAT 585 771 -6.0196 -1.10853 -0.138397 0.0188688 0.00145245 -0.936318 0.350644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -0.00242571 0.0886079 4.00413 -0.0424101 0.494392 +EDGE_SE3:QUAT 651 771 6.65601 0.363103 0.0481521 0.0060129 -0.000717537 -0.98988 0.14178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000129831 0.0247496 4.00051 -0.00941196 0.0805847 +EDGE_SE3:QUAT 652 771 2.53702 0.431966 0.0143743 0.00445847 0.000306725 -0.990192 0.139641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -6.03627e-05 0.0183544 4.00031 -0.00371659 0.0780873 +EDGE_SE3:QUAT 653 771 -1.40409 0.52176 -0.00119912 0.00491866 0.00010545 -0.990488 0.13751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -7.5629e-05 0.0202269 4.00037 -0.00490743 0.0757459 +EDGE_SE3:QUAT 654 771 -5.46199 0.623784 -0.0747155 0.0134666 -0.00100363 -0.990742 0.135087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99941 -0.000606525 0.0553012 4.00266 -0.0181408 0.0738546 +EDGE_SE3:QUAT 700 771 5.95744 1.77055 -0.0764244 -0.00344439 0.0134576 0.52963 0.848115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 0.00164168 0.0835242 4.00046 0.0191086 2.87959 +EDGE_SE3:QUAT 701 771 1.88793 0.743019 -0.00179033 -0.000986402 -0.00141443 0.403599 0.914934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.28288e-06 -0.00440793 4 -0.000363476 3.34843 +EDGE_SE3:QUAT 702 771 -2.11867 0.862405 -0.0219113 -0.000666686 -0.000879049 0.293609 0.955925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.34256e-06 -0.00392898 4 -0.000414882 3.65518 +EDGE_SE3:QUAT 703 771 -6.31011 1.49683 -0.000603565 0.0021344 0.00178658 0.228402 0.973563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.26221e-05 0.00754229 4 0.000594778 3.79134 +EDGE_SE3:QUAT 772 773 4.19119 0.882806 0.0139557 -0.000758226 -0.00364235 0.217708 0.976007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 6.56589e-05 -0.0251744 3.99997 -0.00259121 3.81057 +EDGE_SE3:QUAT 465 772 6.71457 2.11524 0.0666475 -0.00336255 -0.00672765 0.973733 0.22757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.17467e-05 0.0138201 3.99982 0.0292943 0.207427 +EDGE_SE3:QUAT 466 772 1.84226 3.35009 0.0508793 -0.00593847 -0.00571994 0.996515 0.0830042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.00016935 0.0239735 4.0003 0.0264065 0.0278786 +EDGE_SE3:QUAT 467 772 -3.9072 2.78405 0.0441393 0.00295236 0.00549634 -0.989858 0.141926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.70399e-05 0.0122866 4.00014 0.0176026 0.0806906 +EDGE_SE3:QUAT 518 772 3.56536 3.81442 0.0262294 0.00195687 0.00019322 0.361183 0.932493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.91716e-06 -0.00649049 4 -0.00169805 3.4782 +EDGE_SE3:QUAT 519 772 -0.526675 3.93555 0.0129808 0.00195383 0.00249005 0.370555 0.928805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.96781e-05 0.00806883 4 0.000683839 3.45077 +EDGE_SE3:QUAT 520 772 -4.71896 3.98492 -0.0214007 0.00093249 0.002004 0.378656 0.925535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.90673e-05 0.0088786 4 0.00117502 3.4265 +EDGE_SE3:QUAT 581 772 6.91233 -2.07482 0.00203683 0.00606458 0.000734008 -0.919439 0.393185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -0.000272202 0.0295595 4.00041 -0.0142653 0.618671 +EDGE_SE3:QUAT 582 772 2.5216 -2.05357 -0.00335908 0.00665068 0.00107742 -0.922229 0.386586 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.00033141 0.0323678 4.00052 -0.0147122 0.598137 +EDGE_SE3:QUAT 583 772 -1.83723 -1.98806 -0.0395061 0.00666754 0.00225771 -0.922178 0.386702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000361151 0.0329973 4.00063 -0.0117093 0.598489 +EDGE_SE3:QUAT 584 772 -5.59998 -2.42123 -0.160032 0.0146697 0.003351 -0.89869 0.438327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -0.0017983 0.0752943 4.00242 -0.0341885 0.770403 +EDGE_SE3:QUAT 650 772 7.08767 -1.75476 0.0124298 0.00579654 -0.000596926 -0.924268 0.3817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -0.000215109 0.0274115 4.00028 -0.0166877 0.583058 +EDGE_SE3:QUAT 651 772 2.9055 -1.66696 0.00665207 0.00636843 -0.000811824 -0.925001 0.379911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -0.0002553 0.030012 4.00032 -0.0187017 0.577666 +EDGE_SE3:QUAT 652 772 -1.23713 -1.59262 -0.0171999 0.00530089 0.000540787 -0.925874 0.377794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000201655 0.0254706 4.00031 -0.0123054 0.57113 +EDGE_SE3:QUAT 653 772 -5.17826 -1.48126 -0.0404029 0.00581874 0.00026154 -0.926689 0.375785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000235364 0.0277733 4.00035 -0.0143295 0.565121 +EDGE_SE3:QUAT 701 772 4.04955 4.43422 0.00382552 -0.00309738 -0.000576178 0.615524 0.788112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.36487e-06 0.0148433 3.99998 0.00705515 2.48458 +EDGE_SE3:QUAT 702 772 0.83022 3.95842 -0.0133595 -0.00235574 -2.9453e-05 0.518487 0.855082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.92959e-07 0.011883 3.99999 0.00430386 2.92472 +EDGE_SE3:QUAT 703 772 -2.95488 4.15524 -0.00674549 0.00124655 0.00191911 0.459724 0.888059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.18272e-06 0.00484477 4 0.000165652 3.15462 +EDGE_SE3:QUAT 773 774 4.26837 0.572815 0.0408281 -0.00904057 0.0178615 0.121262 0.992419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00551 0.000331661 0.152967 3.99856 0.00943238 3.94702 +EDGE_SE3:QUAT 465 773 2.57599 3.18467 0.0560136 -0.00107695 -0.0072532 0.999921 0.0101636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.71981e-05 0.00430871 3.9998 0.0290923 0.000629458 +EDGE_SE3:QUAT 466 773 -2.44225 3.22148 0.00878181 0.00371922 0.00524664 -0.99063 0.136422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 3.90557e-05 0.0153929 4.00024 0.0160344 0.0745708 +EDGE_SE3:QUAT 581 773 4.61686 -5.69937 -0.029252 0.00263552 -0.00131494 -0.811414 0.584464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -9.43132e-06 0.012298 3.99999 -0.00946547 1.36647 +EDGE_SE3:QUAT 582 773 0.202176 -5.64609 -0.0406896 0.00302414 -0.00118601 -0.815876 0.578218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.24369e-05 0.0146347 3.99999 -0.0105943 1.33744 +EDGE_SE3:QUAT 583 773 -4.14238 -5.57767 -0.0875558 0.00397135 0.000246514 -0.816025 0.578002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -0.000109109 0.0220063 4.00007 -0.0119621 1.33653 +EDGE_SE3:QUAT 650 773 4.71711 -5.31735 -0.0115105 0.00211886 -0.00232228 -0.81887 0.573971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.50447e-05 0.00800022 3.99997 -0.0091187 1.31782 +EDGE_SE3:QUAT 651 773 0.524543 -5.23072 -0.0222659 0.00257976 -0.00300544 -0.820191 0.572076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.55139e-05 0.00950186 3.99995 -0.0113487 1.30916 +EDGE_SE3:QUAT 652 773 -3.64893 -5.13718 -0.050542 0.00223084 -0.00131243 -0.821227 0.570596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.19067e-06 0.0101495 3.99999 -0.00837169 1.30237 +EDGE_SE3:QUAT 774 775 4.25964 0.103679 -0.0216982 -0.00268505 0.0109829 0.0345283 0.99934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00194 -1.80956e-05 0.0888554 3.99951 0.00153356 3.9972 +EDGE_SE3:QUAT 465 774 -1.69265 2.74065 0.0802179 0.0201165 0.0163318 -0.993476 0.111055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99794 0.000234289 0.0820958 4.00699 0.0457745 0.0515743 +EDGE_SE3:QUAT 466 774 -6.39434 1.51151 0.00109706 0.0208355 0.0163031 -0.966653 0.25472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99787 -0.00191393 0.0931564 4.00879 0.0151775 0.26194 +EDGE_SE3:QUAT 775 776 4.20641 -0.0397015 -0.0074006 -0.00161139 0.00477457 0.00888448 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -2.60695e-05 0.0383668 3.99991 0.000169835 4.00005 +EDGE_SE3:QUAT 465 775 -5.828 1.69279 -0.132112 0.0312701 0.0193995 -0.98879 0.144708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99534 -0.00122035 0.129303 4.01753 0.0382952 0.0884261 +EDGE_SE3:QUAT 776 777 4.31457 -0.0812845 0.0294708 0.000669969 0.00727851 0.00419458 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 2.48337e-05 0.0582036 3.99979 0.000122964 4.00078 +EDGE_SE3:QUAT 777 778 4.32846 -0.0934176 0.0628643 -0.000499076 -0.00358197 0.000569271 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 7.32612e-06 -0.0286536 3.99995 -8.31027e-06 4.0002 +EDGE_SE3:QUAT 461 777 3.55132 2.42444 0.0981322 -0.0123051 -0.00616224 0.99987 0.00838364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99941 0.000331513 0.0492253 4.00224 0.0254906 0.00104937 +EDGE_SE3:QUAT 462 777 -0.913763 2.50434 0.048397 -0.0174684 -0.00886612 0.999766 0.00918241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9988 0.000682729 0.0698818 4.0045 0.0368002 0.00189659 +EDGE_SE3:QUAT 463 777 -5.23184 2.49376 -0.000218527 0.0157765 0.0100964 -0.99981 0.00542891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99899 0.000610928 0.0631098 4.00362 0.03975 0.00150836 +EDGE_SE3:QUAT 778 779 4.3663 -0.105466 0.050334 -0.00145826 -0.0046516 -0.00286922 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 2.56962e-05 -0.0372653 3.99991 5.27381e-05 4.00031 +EDGE_SE3:QUAT 460 778 3.29275 2.48839 0.0676947 -0.00144104 -0.00717049 0.999967 0.00359107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.0022e-05 0.00576468 3.99983 0.028722 0.00026614 +EDGE_SE3:QUAT 461 778 -0.76552 2.58679 0.0554205 -0.00877463 -0.00666313 0.99991 0.00765207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000245298 0.0351028 4.00103 0.0271965 0.000727156 +EDGE_SE3:QUAT 462 778 -5.28099 2.67434 -0.034269 -0.0138754 -0.00914314 0.999818 0.009327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99925 0.000544892 0.0555116 4.00269 0.0376377 0.00147237 +EDGE_SE3:QUAT 779 780 4.31953 -0.096571 0.00687569 0.000296537 -0.00115428 -3.56823e-06 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.36928e-06 -0.00923424 3.99999 2.59574e-08 4.00002 +EDGE_SE3:QUAT 459 779 3.0598 2.53946 0.0756223 0.00187189 -0.00853426 0.999957 0.0031624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.54611e-05 -0.00748848 3.99977 0.0340883 0.000344543 +EDGE_SE3:QUAT 460 779 -1.08198 2.63045 0.101474 0.00317804 -0.00865787 0.999937 0.00641394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000112279 -0.0127143 3.99987 0.0344656 0.000501955 +EDGE_SE3:QUAT 461 779 -5.11182 2.76434 0.0236125 -0.00412714 -0.00807299 0.999903 0.0105929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000131855 0.0165128 4 0.0326345 0.000783287 +EDGE_SE3:QUAT 780 781 4.33862 -0.0924573 0.0059376 0.000692244 0.0074277 0.000961058 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00088 2.18519e-05 0.059425 3.99978 2.94873e-05 4.00088 +EDGE_SE3:QUAT 458 780 2.86764 2.56919 0.0742349 0.0048392 0.0076593 -0.999959 0.000153393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000148276 0.0193583 4.00014 0.0306343 0.000328378 +EDGE_SE3:QUAT 459 780 -1.21985 2.65633 0.0993067 0.00295381 -0.00791896 0.99996 0.00289977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.43995e-05 -0.0118165 3.99989 0.0316072 0.000318301 +EDGE_SE3:QUAT 460 780 -5.35729 2.77566 0.132106 0.00414435 -0.00837407 0.999938 0.00610105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000139661 -0.0165799 4 0.033293 0.000494725 +EDGE_SE3:QUAT 781 782 4.33241 -0.0765058 0.0610864 -0.00328945 0.00286447 0.00216972 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -3.74513e-05 0.0230015 3.99997 2.43348e-05 4.00011 +EDGE_SE3:QUAT 457 781 3.07817 2.57085 0.075118 0.00766171 0.00641354 -0.999942 0.00413018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000192188 0.0306485 4.00078 0.0254077 0.000464424 +EDGE_SE3:QUAT 458 781 -1.47159 2.65872 0.0429772 0.0124741 0.00687664 -0.999898 0.0011219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 0.000340061 0.0498959 4.00231 0.0274174 0.000815295 +EDGE_SE3:QUAT 459 781 -5.53789 2.77619 0.127223 -0.00462686 -0.0074006 0.999959 0.00251207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000137168 0.018509 4.00012 0.0296975 0.000331361 +EDGE_SE3:QUAT 782 783 4.19725 -0.0944585 0.0473166 0.00430567 -0.00187417 0.00223955 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.24194e-05 -0.0151087 3.99999 -1.65946e-05 4.00004 +EDGE_SE3:QUAT 456 782 3.13685 2.51612 0.0772705 0.00703723 0.0111785 -0.99987 0.00928474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000312626 0.028157 4.00033 0.0441916 0.00103124 +EDGE_SE3:QUAT 457 782 -1.23038 2.61774 0.0754676 0.0105616 0.0094043 -0.999881 0.00618986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99954 0.00038542 0.0422517 4.00146 0.037112 0.000943765 +EDGE_SE3:QUAT 458 782 -5.73722 2.73738 -0.00461351 0.0155552 0.0102979 -0.999823 0.00262577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99903 0.000629686 0.0622234 4.00347 0.0409164 0.00141374 +EDGE_SE3:QUAT 783 784 4.11241 -0.0714932 0.0186389 0.00095155 -0.00598507 0.00313038 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 -2.01193e-05 -0.0479215 3.99986 -7.42336e-05 4.00053 +EDGE_SE3:QUAT 455 783 2.99911 2.44873 0.0474906 0.00178032 0.0079941 -0.999872 0.0137205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.2718e-05 0.00712418 3.9998 0.0317656 0.00101802 +EDGE_SE3:QUAT 456 783 -1.03667 2.53884 0.0656078 0.00512299 0.00648422 -0.999901 0.0114091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000129288 0.0204969 4.00027 0.0254642 0.000787825 +EDGE_SE3:QUAT 457 783 -5.41829 2.66387 0.0330861 0.00871228 0.00502189 -0.999918 0.00798419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000162073 0.0348523 4.00113 0.0195359 0.00065408 +EDGE_SE3:QUAT 784 785 4.32854 -0.0717106 -0.00145845 -0.00188079 0.00480674 0.00372428 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -3.42055e-05 0.0385401 3.99991 7.07896e-05 4.00032 +EDGE_SE3:QUAT 454 784 3.09591 2.34368 0.0260201 -0.00099809 0.00406347 -0.999807 0.0191962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.4054e-05 -0.00399443 3.99995 0.0163921 0.00154517 +EDGE_SE3:QUAT 455 784 -1.08102 2.41607 0.0552323 -0.00408939 0.00717235 -0.999818 0.0172212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000116608 -0.0163657 4.00004 0.0292331 0.00146695 +EDGE_SE3:QUAT 456 784 -5.17637 2.54263 0.0527001 -0.000704207 0.00588882 -0.999876 0.0145819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.26623e-05 -0.00281771 3.99987 0.0236245 0.000992077 +EDGE_SE3:QUAT 785 786 4.1456 -0.0612538 0.0186165 0.000332817 0.00108964 0.00585129 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.61137e-06 0.00869331 4 2.54201e-05 3.99988 +EDGE_SE3:QUAT 453 785 3.06471 2.16068 0.0545257 0.0052277 0.0082106 -0.999634 0.0252363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000167032 0.0209334 4.00022 0.0317396 0.00290911 +EDGE_SE3:QUAT 454 785 -1.24904 2.25099 0.0401266 0.00404044 0.00664785 -0.999699 0.023281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000105627 0.0161764 4.00011 0.0258052 0.00240004 +EDGE_SE3:QUAT 455 785 -5.4259 2.34553 0.09296 0.000873799 0.00988726 -0.999726 0.0211944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.04568e-05 0.00349896 3.99963 0.0393549 0.00218728 +EDGE_SE3:QUAT 786 787 4.13794 -0.067605 0.0594465 0.00441205 0.0018584 0.00264623 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.26013e-05 0.0147267 3.99999 1.97841e-05 4.00003 +EDGE_SE3:QUAT 452 786 3.16279 1.9517 0.0105167 0.00555945 0.00214921 -0.999402 0.0340602 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 2.29657e-05 0.0222768 4.00049 0.00705999 0.00477707 +EDGE_SE3:QUAT 453 786 -1.04185 2.01996 0.0263061 0.00628166 0.00828445 -0.99946 0.0311724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000192601 0.0251668 4.00043 0.0314987 0.00429365 +EDGE_SE3:QUAT 454 786 -5.34724 2.12049 0.0310413 0.00493033 0.0063113 -0.999532 0.0295076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000114951 0.0197491 4.00027 0.0240305 0.00372488 +EDGE_SE3:QUAT 787 788 4.3733 -0.12736 0.0187112 -0.00102237 -0.0030261 -0.0116979 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 9.87699e-06 -0.0243481 3.99996 0.000142468 3.9996 +EDGE_SE3:QUAT 451 787 3.36148 1.57128 0.0399406 0.00205636 0.00372112 -0.999505 0.0311839 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.04136e-05 0.00823847 4.00002 0.0143361 0.00395817 +EDGE_SE3:QUAT 452 787 -0.954091 1.73921 0.0293714 0.00789088 -0.00206615 -0.999295 0.0366535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 -0.000117279 0.0316258 4.00095 -0.0105513 0.00565216 +EDGE_SE3:QUAT 453 787 -5.13658 1.8241 0.0354313 0.00832035 0.00373296 -0.999383 0.0339225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 6.95777e-05 0.033339 4.0011 0.0126382 0.00492114 +EDGE_SE3:QUAT 788 789 4.07087 -0.357701 0.0694805 -0.00159725 -0.0211336 -0.0958667 0.995169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0071 -0.00089449 -0.168832 3.99829 0.00810563 3.97035 +EDGE_SE3:QUAT 450 788 3.30921 1.19372 0.0405112 -0.0117392 -0.00510258 0.999552 0.027063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.000321043 0.0470073 4.00202 0.0229297 0.00361392 +EDGE_SE3:QUAT 451 788 -0.981429 1.441 0.0418343 -0.00100255 0.0046547 -0.999802 0.0193106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.56783e-05 -0.00401228 3.99993 0.0187561 0.00158361 +EDGE_SE3:QUAT 452 788 -5.31154 1.54925 -0.0164793 0.00504635 -0.000655853 -0.999684 0.0246146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.80595e-05 0.0202035 4.0004 -0.00361309 0.00252889 +EDGE_SE3:QUAT 789 790 4.09232 -0.683856 -0.00222653 -0.000473631 0.0025945 -0.174731 0.984613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -2.89804e-05 0.0188402 3.99998 -0.00158893 3.87796 +EDGE_SE3:QUAT 449 789 3.81837 1.0985 0.0249349 -0.00371084 -0.0147538 0.958934 0.283222 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000280633 0.0138348 3.99918 0.0552448 0.321743 +EDGE_SE3:QUAT 450 789 -0.714664 1.78677 0.0199552 0.0100243 -0.00829263 0.992369 0.122618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 -2.9459e-05 -0.0411101 4.00177 0.0222575 0.0606975 +EDGE_SE3:QUAT 451 789 -5.05556 1.66683 0.129564 0.0224854 -0.00589296 0.996758 0.0770239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99791 0.000422124 -0.0907331 4.00831 0.00946601 0.0258252 +EDGE_SE3:QUAT 790 791 4.11578 -0.96187 -0.00389791 0.000748986 -0.000453994 -0.230525 0.973066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.034e-07 -0.0013478 4 6.42918e-05 3.78743 +EDGE_SE3:QUAT 395 790 0.388352 6.09019 -0.0166205 -0.0010918 0.007497 -0.871739 0.489913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 6.21813e-05 0.00141772 4 0.0168455 0.960184 +EDGE_SE3:QUAT 396 790 -3.77665 6.18291 -0.010245 -0.00124047 0.00941659 -0.873662 0.486441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 9.37143e-05 0.00228444 4 0.0210203 0.946698 +EDGE_SE3:QUAT 448 790 6.6397 2.09992 0.0693195 -0.00654935 -0.013452 0.765922 0.64276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -0.000321814 0.00806738 3.99981 0.0269186 1.65313 +EDGE_SE3:QUAT 449 790 0.759323 3.88772 0.0529038 -0.00368116 -0.0148395 0.894857 0.446091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 -0.000386881 0.00788021 3.99958 0.0425006 0.796641 +EDGE_SE3:QUAT 450 790 -4.5065 3.43381 0.116241 0.00864355 -0.006539 0.955767 0.293925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000442238 -0.0400823 4.00152 0.00210948 0.346012 +EDGE_SE3:QUAT 791 792 4.06419 -1.09746 -0.0057434 -0.00041761 0.00903078 -0.26123 0.965234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -0.000448282 0.0637419 3.99985 -0.00793748 3.72804 +EDGE_SE3:QUAT 393 791 5.90168 2.90991 -0.00344023 -0.00119625 0.00844772 -0.958206 0.285953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000105025 -0.00375414 3.99979 0.0295965 0.327324 +EDGE_SE3:QUAT 394 791 1.70553 2.97096 -0.00688612 8.67084e-05 0.00711201 -0.959713 0.280892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.42153e-05 0.0016467 3.99992 0.0228149 0.315747 +EDGE_SE3:QUAT 395 791 -2.55749 3.09091 -0.029568 -0.00287837 0.00603986 -0.961172 0.275868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.51497e-05 -0.0117368 3.99984 0.0255557 0.304624 +EDGE_SE3:QUAT 396 791 -6.74329 3.20699 -0.0270834 -0.00341678 0.00766741 -0.962243 0.272063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.06987e-05 -0.0138635 3.99974 0.0320286 0.296399 +EDGE_SE3:QUAT 792 793 3.89995 -1.0969 0.00372008 0.00481161 0.00331292 -0.264718 0.964308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -2.96381e-05 0.0383401 3.99991 -0.00561645 3.72006 +EDGE_SE3:QUAT 392 792 6.1391 1.52461 0.0244084 0.00541198 0.0107171 -0.99954 0.027856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000235139 0.021678 4.00009 0.0415853 0.00365406 +EDGE_SE3:QUAT 393 792 1.90147 1.60203 -0.00206431 0.00547978 0.0107059 -0.9996 0.0255874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000237245 0.0219452 4.0001 0.0416378 0.00317304 +EDGE_SE3:QUAT 394 792 -2.25296 1.71097 -0.0137668 0.00709792 0.00959388 -0.999716 0.0206423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000260921 0.0284132 4.00051 0.0371723 0.00225187 +EDGE_SE3:QUAT 395 792 -6.53339 1.84583 -0.00454308 0.00441868 0.00778309 -0.99984 0.0154851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000137304 0.0176827 4.0001 0.030569 0.001271 +EDGE_SE3:QUAT 793 794 4.10617 -1.1957 0.00539894 -0.000456464 -0.00144318 -0.272988 0.962016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.17886e-05 -0.0117003 3.99999 0.00160283 3.70195 +EDGE_SE3:QUAT 391 793 6.41863 2.32439 0.0173283 -0.00789688 -0.00614799 0.971468 0.23696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000294343 0.0334847 4.00025 0.0353433 0.225215 +EDGE_SE3:QUAT 392 793 2.19468 2.39713 0.00419193 -0.00602644 -0.00700716 0.971241 0.237918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000140582 0.025312 3.99994 0.0349641 0.226904 +EDGE_SE3:QUAT 393 793 -2.02102 2.49824 -0.0137336 -0.00590709 -0.00689101 0.970665 0.240264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000133245 0.0248222 3.99994 0.0343672 0.231376 +EDGE_SE3:QUAT 394 793 -6.2265 2.64669 -0.0453674 -0.00775241 -0.00630009 0.969312 0.245631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000276631 0.0329448 4.00019 0.0358 0.241955 +EDGE_SE3:QUAT 794 795 3.88138 -0.870023 -0.00773395 -0.00134691 -0.00203826 -0.189484 0.981881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.04505e-05 -0.0184254 3.99998 0.00181376 3.85647 +EDGE_SE3:QUAT 337 794 3.02199 4.60832 0.0787107 0.00254207 0.0149459 -0.924805 0.38014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99954 7.27678e-05 0.0186877 4.00057 0.0327081 0.578513 +EDGE_SE3:QUAT 338 794 -3.02488 4.57514 0.0684278 0.00346982 0.0144266 -0.834116 0.551389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 -0.000722124 0.0379595 4.00129 0.00820837 1.21676 +EDGE_SE3:QUAT 391 794 3.32223 5.262 -0.0085247 -0.00477161 -0.00851427 0.86975 0.493396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000164524 0.0165015 3.99971 0.0294468 0.974136 +EDGE_SE3:QUAT 392 794 -0.905765 5.35234 -0.00833487 -0.00252883 -0.00904887 0.869491 0.493859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000140936 0.00436561 3.99988 0.0236744 0.975817 +EDGE_SE3:QUAT 795 796 4.0695 -0.463408 -0.0200019 0.00558349 0.047573 -0.070687 0.996348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0367 -0.00281792 0.385539 3.99101 -0.0136668 4.01683 +EDGE_SE3:QUAT 337 795 -0.345554 2.46629 0.041831 -0.00274126 0.0155479 -0.980142 0.197667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000214998 -0.0106258 3.99905 0.0603577 0.157267 +EDGE_SE3:QUAT 338 795 -5.30644 1.33778 0.00319727 -0.00174717 0.0149269 -0.923606 0.383048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000344384 -0.00163534 3.99967 0.0435364 0.587511 +EDGE_SE3:QUAT 796 797 4.05616 -0.114537 0.0411854 -0.00139483 -0.00736549 -0.00464621 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00086 3.51328e-05 -0.0590108 3.99978 0.000135405 4.00078 +EDGE_SE3:QUAT 337 796 -4.25456 1.31741 0.0243351 0.0439473 0.0191827 -0.990746 0.126976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99157 -0.00280994 0.180049 4.03334 0.0299325 0.0729862 +EDGE_SE3:QUAT 797 798 4.38186 -0.0869689 0.0266522 -0.00010448 -0.000840377 0.00364812 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.12654e-07 -0.00671832 4 -1.22536e-05 3.99996 +EDGE_SE3:QUAT 798 799 4.33554 -0.0662398 -0.00177652 0.00170093 -0.00114998 0.00510153 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.77719e-06 -0.00930364 3.99999 -2.3765e-05 3.99992 +EDGE_SE3:QUAT 799 800 4.30093 -0.0853015 0.0176645 3.68821e-05 0.00434449 0.000222457 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 7.41882e-07 0.0347581 3.99992 3.88356e-06 4.0003 +EDGE_SE3:QUAT 332 799 4.75245 2.45847 0.0388688 0.00126705 -0.00750605 0.999918 0.0102959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.22162e-05 -0.00506952 3.99981 0.0299114 0.000654156 +EDGE_SE3:QUAT 333 799 0.347867 2.50084 0.0658814 0.00455084 -0.00676594 0.999778 0.0194307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.0001199 -0.018215 4.00018 0.0263337 0.00176661 +EDGE_SE3:QUAT 334 799 -3.75734 2.63254 -0.00216011 -0.00536617 -0.0055165 0.999587 0.0276725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000129381 0.0214893 4.0003 0.0232139 0.0033134 +EDGE_SE3:QUAT 800 801 4.28916 -0.088073 0.0501631 -0.000731111 0.0024988 0.000325405 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -7.26085e-06 0.0199937 3.99998 3.1438e-06 4.0001 +EDGE_SE3:QUAT 331 800 4.86993 2.54537 0.0804634 -0.00769118 -0.00708988 0.999933 0.00500145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000223277 0.0307674 4.00073 0.028674 0.000542228 +EDGE_SE3:QUAT 332 800 0.463161 2.63015 0.0734322 -0.00297774 -0.00710403 0.999921 0.00993013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.25887e-05 0.0119135 3.99993 0.0286462 0.000635088 +EDGE_SE3:QUAT 333 800 -3.92496 2.75296 0.134496 0.000328922 -0.00631366 0.999797 0.0191426 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.43022e-05 -0.00131688 3.99984 0.0251807 0.00162477 +EDGE_SE3:QUAT 801 802 4.26797 -0.0891529 0.0550608 -0.000510165 -0.00304568 0.000552534 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 6.33784e-06 -0.0243629 3.99996 -6.84455e-06 4.00015 +EDGE_SE3:QUAT 330 801 5.01519 2.59119 0.115718 -0.012431 -0.00797952 0.999889 0.00215667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99939 0.000404453 0.0497255 4.00221 0.0321584 0.000895178 +EDGE_SE3:QUAT 331 801 0.575364 2.67856 0.0691567 -0.0100597 -0.00793925 0.999905 0.00512581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000329605 0.0402423 4.00135 0.0321842 0.000768829 +EDGE_SE3:QUAT 332 801 -3.8249 2.80449 0.0960345 -0.00565235 -0.00834798 0.999897 0.0101738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000190614 0.0226149 4.00021 0.0338478 0.000828319 +EDGE_SE3:QUAT 802 803 4.22692 -0.0903202 0.0127876 0.000771954 -0.0024682 0.000984881 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -7.48256e-06 -0.0197551 3.99998 -9.61738e-06 4.00009 +EDGE_SE3:QUAT 329 802 4.75908 2.60692 0.0702559 -0.00333022 -0.0076665 0.999965 0.000510802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000102024 0.013322 3.99994 0.0306805 0.000280735 +EDGE_SE3:QUAT 330 802 0.77679 2.69384 0.0620366 -0.00946048 -0.00854876 0.999917 0.00168027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000326471 0.0378446 4.00113 0.0343376 0.000664012 +EDGE_SE3:QUAT 331 802 -3.6446 2.80208 0.0371188 -0.00714735 -0.00825071 0.99993 0.00465214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000239105 0.0285926 4.00053 0.0332752 0.000567718 +EDGE_SE3:QUAT 803 804 4.34314 -0.094092 0.00832588 0.00129835 0.00565928 0.00146274 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 3.05078e-05 0.0452563 3.99987 3.4102e-05 4.0005 +EDGE_SE3:QUAT 328 803 5.00269 2.63138 0.018451 -0.00587587 0.00609466 -0.999964 0.000720489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.000143686 -0.0235044 4.0004 0.0244167 0.000289214 +EDGE_SE3:QUAT 329 803 0.567242 2.71419 0.0516314 0.000792153 0.00697369 -0.999975 0.000631866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.23311e-05 0.00316885 3.99982 0.0278901 0.000198581 +EDGE_SE3:QUAT 330 803 -3.45728 2.80821 0.00187157 -0.00701965 -0.00748814 0.999947 0.000888717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000211027 0.0280803 4.00056 0.0300097 0.000425387 +EDGE_SE3:QUAT 804 805 4.27335 -0.0789628 0.0328462 -0.00133664 -0.000830493 0.00197921 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.44451e-06 -0.00661216 4 -6.55495e-06 4 +EDGE_SE3:QUAT 327 804 5.07091 2.65001 0.0500892 0.00233424 0.0072891 -0.999939 0.0079884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.0337e-05 0.00933861 3.99988 0.0290028 0.00048737 +EDGE_SE3:QUAT 328 804 0.706998 2.70235 0.0782516 -0.000353395 0.00480426 -0.999985 0.00245965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.34347e-06 -0.00141364 3.99991 0.0192235 0.000117088 +EDGE_SE3:QUAT 329 804 -3.75225 2.7991 0.0553444 0.00648451 0.0053765 -0.999962 0.00203609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000137937 0.0259388 4.00056 0.0214048 0.000299312 +EDGE_SE3:QUAT 805 806 4.2272 -0.080251 0.0457197 -0.00124511 0.00374791 0.00196639 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -1.80301e-05 0.0300139 3.99994 2.9103e-05 4.00021 +EDGE_SE3:QUAT 326 805 5.14533 2.62678 0.0703936 0.00617381 0.00807503 -0.999775 0.0186396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000191063 0.0247102 4.00039 0.0313577 0.00178832 +EDGE_SE3:QUAT 327 805 0.824971 2.65399 0.0645114 0.00136487 0.00845266 -0.999914 0.00997802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.13229e-05 0.00546096 3.99975 0.0336925 0.000689541 +EDGE_SE3:QUAT 328 805 -3.52645 2.78015 0.114648 -0.000939215 0.00607614 -0.999973 0.00395568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.17356e-05 -0.00375715 3.99987 0.024333 0.000214149 +EDGE_SE3:QUAT 806 807 4.23847 -0.085425 0.02388 0.00231204 -0.00636305 0.00235264 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -5.66882e-05 -0.0509761 3.99984 -5.77634e-05 4.00063 +EDGE_SE3:QUAT 325 806 5.25036 2.52201 0.102588 0.0116 0.00798557 -0.999475 0.0291697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99942 0.000286908 0.0464602 4.00202 0.029191 0.00415676 +EDGE_SE3:QUAT 326 806 0.929268 2.55192 0.0692288 0.00979639 0.00983421 -0.999688 0.0207491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000351444 0.0392142 4.00124 0.037688 0.00246184 +EDGE_SE3:QUAT 327 806 -3.38153 2.67171 0.102716 0.00525477 0.0103329 -0.99986 0.0120255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000219029 0.0210267 4.00005 0.0408157 0.00110551 +EDGE_SE3:QUAT 807 808 4.1525 -0.0709792 -0.000385074 -0.000329812 -0.000426831 0.0021357 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.70535e-07 -0.00340617 4 -3.6357e-06 3.99998 +EDGE_SE3:QUAT 324 807 5.13355 2.31911 0.03714 -0.000762771 0.00557913 -0.999228 0.0388828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.53527e-06 -0.00305546 3.99988 0.0224688 0.00617625 +EDGE_SE3:QUAT 325 807 1.01064 2.3531 0.0306518 0.00532904 0.00539731 -0.99947 0.0316489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 9.90615e-05 0.0213499 4.00038 0.0201903 0.00422269 +EDGE_SE3:QUAT 326 807 -3.28134 2.46442 0.0134634 0.00370658 0.0072697 -0.999683 0.0238111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000109017 0.0148407 4.00004 0.0283336 0.00252378 +EDGE_SE3:QUAT 808 809 4.15233 -0.109902 0.00323756 -3.0908e-06 0.00649189 -0.0124346 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 -1.26563e-05 0.0519303 3.99983 -0.000322986 4.00006 +EDGE_SE3:QUAT 323 808 4.98073 1.97709 0.011172 -0.00435252 0.00673245 -0.999006 0.0438478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.00011773 -0.0174569 4.00006 0.0283261 0.00796779 +EDGE_SE3:QUAT 324 808 0.995698 2.06215 0.0404292 -0.00109305 0.00622898 -0.999137 0.0410487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.5028e-05 -0.00437999 3.99985 0.025169 0.00690343 +EDGE_SE3:QUAT 325 808 -3.11788 2.16644 -0.0167071 0.0054044 0.006116 -0.999381 0.0342268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000116035 0.0216581 4.00037 0.0229179 0.00493476 +EDGE_SE3:QUAT 809 810 4.06575 -0.235219 0.033063 -0.00157492 -0.0152673 -0.060871 0.998028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00375 -0.0002466 -0.122709 3.99907 0.00373981 3.98894 +EDGE_SE3:QUAT 322 809 5.26675 1.20985 0.117119 -0.0170799 -0.0112146 0.99938 0.0286703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99893 0.000930716 0.0684106 4.00389 0.0487533 0.00505289 +EDGE_SE3:QUAT 323 809 0.841087 1.71497 0.0509272 0.00212464 0.00699467 -0.999474 0.0316015 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.73914e-05 0.00851367 3.9999 0.0273725 0.00420026 +EDGE_SE3:QUAT 324 809 -3.11729 1.84088 0.0529899 0.00544515 0.00627407 -0.999552 0.0287408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000123496 0.0218094 4.00036 0.0237972 0.00356483 +EDGE_SE3:QUAT 810 811 4.10644 -0.600074 0.0173586 0.00288982 -0.00281865 -0.150915 0.988538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.95034e-05 -0.0166292 3.99999 0.00110391 3.90897 +EDGE_SE3:QUAT 321 810 5.54644 0.639893 0.0507044 -0.00858541 -0.0164611 0.975507 0.219183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000130899 0.0353488 3.99897 0.072393 0.193854 +EDGE_SE3:QUAT 322 810 1.23102 1.67326 0.0208854 -0.00114638 -0.0142903 0.995906 0.0892551 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.06014e-05 0.00455802 3.99919 0.0568321 0.0326853 +EDGE_SE3:QUAT 323 810 -3.20056 1.71332 0.0665995 0.0136594 -0.00822352 0.999442 0.0293371 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99921 -0.000328859 -0.0547075 4.00287 0.0296502 0.00441147 +EDGE_SE3:QUAT 324 810 -7.178 1.86468 0.0474451 0.0104401 -0.00777959 0.999391 0.0323774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -0.000250966 -0.0418279 4.00162 0.0283522 0.00483219 +EDGE_SE3:QUAT 811 812 4.20613 -0.967857 0.00819396 0.00230363 -0.00333041 -0.228244 0.973596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -5.40209e-05 -0.0184983 3.99999 0.00178958 3.7917 +EDGE_SE3:QUAT 320 811 7.14991 0.846101 0.0515625 -0.00780417 -0.0134509 0.832496 0.553812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -0.000458897 0.0236502 3.9994 0.0412797 1.22769 +EDGE_SE3:QUAT 321 811 2.10951 2.95965 0.0524161 -0.00258144 -0.0150921 0.931243 0.364077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000376508 0.00633566 3.99947 0.0478385 0.530916 +EDGE_SE3:QUAT 322 811 -2.68547 2.99789 0.0632632 0.00407423 -0.0114931 0.971131 0.238233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 -0.000130805 -0.018867 4.0004 0.0322627 0.227403 +EDGE_SE3:QUAT 812 813 4.01311 -1.01662 -0.00278032 -0.000442588 0.00440396 -0.247194 0.968956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.000102773 0.0307943 3.99996 -0.00361378 3.75582 +EDGE_SE3:QUAT 264 812 5.52946 4.80037 0.0270187 0.00108176 0.00848163 -0.934185 0.356686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 5.79287e-05 0.00814992 4.0001 0.0209373 0.509062 +EDGE_SE3:QUAT 265 812 1.35791 4.84939 -0.0205593 -0.00119228 0.00692414 -0.937477 0.347976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.83965e-05 -0.00321943 3.99988 0.0225942 0.484503 +EDGE_SE3:QUAT 266 812 -2.84423 4.96978 -0.0554757 -0.00216127 0.00499472 -0.941224 0.337739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.09182e-05 -0.00845398 3.99989 0.0196879 0.4564 +EDGE_SE3:QUAT 321 812 -0.316003 6.50432 0.121095 0.00503366 -0.0139837 0.823674 0.566869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.00107175 -0.04762 4.00158 0.000956784 1.28621 +EDGE_SE3:QUAT 813 814 3.9503 -1.13785 -0.0110991 0.00150337 0.00724563 -0.27624 0.96106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00078 -0.000302767 0.0561981 3.99987 -0.00767028 3.69555 +EDGE_SE3:QUAT 263 813 6.16427 2.82173 0.00344467 0.00153688 0.00812345 -0.992676 0.120523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.13448e-05 0.00639451 3.99987 0.0298597 0.0583405 +EDGE_SE3:QUAT 264 813 1.87648 2.88091 0.00390756 0.00277499 0.0103176 -0.993316 0.114934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000162022 0.0114446 3.99989 0.0373978 0.053228 +EDGE_SE3:QUAT 265 813 -2.31139 2.9923 -0.0175699 0.00132085 0.00833929 -0.994427 0.105086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.76211e-05 0.00544836 3.99983 0.0313415 0.0444285 +EDGE_SE3:QUAT 266 813 -6.54501 3.18641 -0.0446326 0.000865364 0.00639304 -0.995468 0.0948806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.70634e-05 0.00355189 3.99988 0.0243474 0.0361622 +EDGE_SE3:QUAT 814 815 3.98901 -1.17664 -0.00125463 -0.00175449 0.000433857 -0.274068 0.961709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.80875e-06 -0.00239403 4 0.000609745 3.69955 +EDGE_SE3:QUAT 262 814 6.50644 2.93674 -0.0075178 -0.00785935 -0.0054466 0.988031 0.153959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000293634 0.0323796 4.00052 0.0299639 0.0953083 +EDGE_SE3:QUAT 263 814 2.05211 2.98988 -0.0127059 -0.00669942 -0.00792331 0.987238 0.158913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000221193 0.0275429 4.00008 0.0380157 0.101576 +EDGE_SE3:QUAT 264 814 -2.20658 3.09559 -0.0164809 -0.00756488 -0.0105755 0.986328 0.164282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000270758 0.0310909 3.99989 0.0491527 0.108819 +EDGE_SE3:QUAT 265 814 -6.42333 3.2791 -0.0282668 -0.00652314 -0.00809694 0.984716 0.173858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000201045 0.0269119 4 0.0387678 0.121476 +EDGE_SE3:QUAT 815 816 3.95965 -0.899238 0.0113581 0.00187678 0.00166309 -0.200655 0.979659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.93467e-06 0.0169073 3.99998 -0.00181946 3.83902 +EDGE_SE3:QUAT 209 815 3.52894 5.35303 0.0611868 0.00422068 0.0127994 -0.914449 0.404477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000212882 0.027262 4.00097 0.0200833 0.654811 +EDGE_SE3:QUAT 210 815 -3.26075 5.34116 0.0900226 -0.0010271 0.0172841 -0.803452 0.595118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99945 -0.000293584 0.0234973 4.00078 0.0193587 1.41732 +EDGE_SE3:QUAT 262 815 3.05792 5.26664 -0.0458356 -0.00678596 -0.00886077 0.907833 0.419184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.58913e-05 0.028084 3.9996 0.039624 0.703537 +EDGE_SE3:QUAT 263 815 -1.36163 5.34623 -0.0332948 -0.00492128 -0.0109318 0.905912 0.423296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000225423 0.0175904 3.99953 0.0390942 0.717279 +EDGE_SE3:QUAT 816 817 4.31125 -0.679321 -0.0673986 0.00567872 0.0381672 -0.116245 0.992471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.02354 -0.00326519 0.308615 3.99441 -0.0180476 3.96962 +EDGE_SE3:QUAT 209 816 0.213007 3.02218 0.0187852 0.00368091 0.0123467 -0.977195 0.211954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000201009 0.0166233 4.00021 0.0379731 0.180157 +EDGE_SE3:QUAT 210 816 -5.27592 1.82803 0.0577592 -0.0020769 0.0162359 -0.906559 0.421761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99958 0.000383237 -0.000464361 3.99974 0.0436965 0.712197 +EDGE_SE3:QUAT 817 818 4.40724 -0.21231 0.0325436 0.00185854 0.000772041 -0.0188383 0.999821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.95735e-06 0.00659307 4 -6.33807e-05 3.99859 +EDGE_SE3:QUAT 209 817 -3.97538 1.86417 -0.0865932 0.0407029 0.0151683 -0.994404 0.0962962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99291 -0.00145887 0.16499 4.02788 0.0283955 0.0441804 +EDGE_SE3:QUAT 818 819 4.14558 -0.082666 0.038771 0.00197874 -0.00248182 0.00545054 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.90007e-05 -0.0199834 3.99997 -5.4285e-05 3.99998 +EDGE_SE3:QUAT 819 820 4.37245 -0.0590294 0.0331504 -0.00196189 0.000466202 0.00674997 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.82847e-06 0.00388825 4 1.32904e-05 3.99982 +EDGE_SE3:QUAT 820 821 4.00478 -0.0546544 0.0284317 -0.00267101 0.00319586 0.00554599 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -3.30894e-05 0.0257441 3.99996 7.08972e-05 4.00004 +EDGE_SE3:QUAT 204 820 4.30842 2.57205 0.053775 -0.00100131 -0.00679153 0.999962 0.00540462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.53228e-05 0.00400566 3.99983 0.0272069 0.000305918 +EDGE_SE3:QUAT 205 820 0.263814 2.65851 0.0511717 -0.00529861 -0.00632904 0.999941 0.00702258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000136557 0.021197 4.00028 0.0256141 0.000473611 +EDGE_SE3:QUAT 206 820 -4.08813 2.7726 -0.00632562 -0.0097714 -0.00665967 0.99985 0.0126644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000284475 0.0390961 4.00131 0.0276315 0.00121457 +EDGE_SE3:QUAT 821 822 4.09256 -0.0841269 0.0172416 0.00353658 -0.00114545 0.0034837 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.64395e-05 -0.00931114 3.99999 -1.61903e-05 3.99997 +EDGE_SE3:QUAT 203 821 4.48168 2.57775 0.0744608 0.00530912 0.00904445 -0.999945 0.000754346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000192099 0.0212388 4.00013 0.0361499 0.000441726 +EDGE_SE3:QUAT 204 821 0.32093 2.67193 0.0760036 0.00443474 0.0093244 -0.999947 9.2681e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000165443 0.0177411 3.99997 0.0372967 0.000426473 +EDGE_SE3:QUAT 205 821 -3.73118 2.76627 0.0367977 -0.00843862 -0.00889158 0.999923 0.00166117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000302156 0.0337575 4.00082 0.0356907 0.000614298 +EDGE_SE3:QUAT 822 823 4.22074 -0.0758131 0.0198838 -0.000207337 -0.00247348 0.00194285 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 2.33604e-06 -0.0197833 3.99998 -1.9248e-05 4.00008 +EDGE_SE3:QUAT 202 822 4.52078 2.55636 0.0678836 0.00457488 0.00646432 -0.999956 0.00503583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000117425 0.0183011 4.00017 0.0256738 0.000349951 +EDGE_SE3:QUAT 203 822 0.403437 2.65787 0.0537579 0.00423609 0.00576942 -0.999965 0.00438071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 9.70277e-05 0.0169455 4.00016 0.0229301 0.000279992 +EDGE_SE3:QUAT 204 822 -3.72484 2.74663 0.0647876 0.00338714 0.00575392 -0.999973 0.00319581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.79188e-05 0.0135494 4.00005 0.0229296 0.000218188 +EDGE_SE3:QUAT 823 824 4.26399 -0.0827924 0.0148696 -0.000412671 0.0022666 0.00236084 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -3.45349e-06 0.0181447 3.99998 2.1373e-05 4.00006 +EDGE_SE3:QUAT 201 823 4.63163 2.51151 0.0446971 0.00120972 0.00530714 -0.999956 0.00770276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.712e-05 0.00483953 3.99991 0.0211508 0.000355033 +EDGE_SE3:QUAT 202 823 0.318475 2.59648 0.0494708 0.00237248 0.00658089 -0.999947 0.00750697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.39821e-05 0.00949134 3.99992 0.0261777 0.00041927 +EDGE_SE3:QUAT 203 823 -3.80154 2.6903 0.0380916 0.00211771 0.0060588 -0.999959 0.00637919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.24759e-05 0.00847182 3.99993 0.0241249 0.000326229 +EDGE_SE3:QUAT 824 825 4.42194 -0.0985378 0.0285092 0.00171166 0.00408522 -0.000225603 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 2.78914e-05 0.0326882 3.99993 -3.0023e-06 4.00027 +EDGE_SE3:QUAT 200 824 4.49568 2.42682 0.057692 0.00420964 0.0050736 -0.999929 0.00996738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.31272e-05 0.0168416 4.00019 0.0199555 0.00056787 +EDGE_SE3:QUAT 201 824 0.37962 2.52161 0.0495131 0.0035698 0.00574182 -0.999929 0.00978664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.14605e-05 0.0142819 4.00008 0.0226836 0.000562755 +EDGE_SE3:QUAT 202 824 -3.91303 2.6162 0.0442577 0.00462967 0.00701527 -0.999919 0.00953358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000128602 0.0185224 4.00016 0.0277043 0.000641221 +EDGE_SE3:QUAT 825 826 4.21218 -0.094331 0.023298 9.77723e-05 -0.000975392 -0.00139649 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.13239e-07 -0.0078015 4 5.44925e-06 4.00001 +EDGE_SE3:QUAT 199 825 4.29108 2.34351 0.0632432 0.00438672 0.00493388 -0.999941 0.00861272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 8.41907e-05 0.0175493 4.00022 0.0194315 0.000468111 +EDGE_SE3:QUAT 200 825 0.0749044 2.44022 0.0477611 0.00835808 0.00289734 -0.999914 0.00964442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 8.12901e-05 0.0334361 4.0011 0.010946 0.000681544 +EDGE_SE3:QUAT 201 825 -4.00843 2.54663 0.0451232 0.00767016 0.00397226 -0.999917 0.00954588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000109517 0.0306846 4.00089 0.0153046 0.00065846 +EDGE_SE3:QUAT 826 827 4.09733 -0.102207 0.037841 -0.000184264 -0.000128399 -0.00177767 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.44116e-08 -0.00103112 4 9.17581e-07 3.99999 +EDGE_SE3:QUAT 198 826 4.26795 2.27167 0.0380109 0.00273041 0.00500757 -0.999965 0.00607497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.47934e-05 0.0109226 4.00002 0.0198963 0.000276416 +EDGE_SE3:QUAT 199 826 0.0735232 2.37516 0.0539413 0.00349075 0.00472582 -0.999953 0.00770269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.50562e-05 0.0139646 4.00011 0.0186865 0.000373379 +EDGE_SE3:QUAT 200 826 -4.10357 2.45885 0.00609937 0.00742342 0.00308333 -0.999932 0.00848345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 8.09437e-05 0.0296964 4.00085 0.0118309 0.000543358 +EDGE_SE3:QUAT 827 828 4.25604 -0.107965 0.0239498 -0.00014733 0.0019182 -0.00320952 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.41318e-06 0.0153399 3.99999 -2.46277e-05 4.00002 +EDGE_SE3:QUAT 197 827 4.19589 2.22603 0.0517536 5.85516e-05 0.00755831 -0.999966 0.00323186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.24636e-06 0.000234243 3.99977 0.0302301 0.000270273 +EDGE_SE3:QUAT 198 827 0.187202 2.32933 0.0647207 0.0027169 0.00553415 -0.99997 0.00463137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.04393e-05 0.0108684 4 0.0220353 0.00023672 +EDGE_SE3:QUAT 199 827 -3.99274 2.41583 0.0630135 0.00331643 0.00538068 -0.999961 0.00611912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.11449e-05 0.013267 4.00007 0.0213594 0.000307835 +EDGE_SE3:QUAT 828 829 4.0657 -0.107128 0.0465167 -0.00155127 0.00170787 -0.00282123 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.07397e-05 0.0136104 3.99999 -1.92827e-05 4.00001 +EDGE_SE3:QUAT 196 828 4.00868 2.22385 0.0654345 -0.00545973 -0.00612091 0.999966 0.00107788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000134165 0.0218399 4.00033 0.0245342 0.000274356 +EDGE_SE3:QUAT 197 828 -0.0374042 2.30424 0.0788292 0.00202916 0.00757404 -0.999969 0.000226701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.1554e-05 0.00811734 3.99984 0.0302923 0.000246092 +EDGE_SE3:QUAT 198 828 -4.0215 2.41218 0.0609404 0.0048472 0.00577725 -0.99997 0.0015743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000111572 0.0193896 4.00024 0.0230504 0.000236722 +EDGE_SE3:QUAT 829 830 4.03322 -0.0913718 0.0244717 -0.00218368 0.0064488 -0.00133668 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -5.76424e-05 0.0515623 3.99983 -3.66458e-05 4.00066 +EDGE_SE3:QUAT 195 829 4.29004 2.27749 0.0485871 -0.00118535 -0.00590776 0.999981 0.00113434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.77305e-05 0.00474164 3.99988 0.0236415 0.000150502 +EDGE_SE3:QUAT 196 829 -0.0345776 2.3316 0.0728253 -0.00704413 -0.00788066 0.999937 0.00386563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000224804 0.0281792 4.00054 0.0317469 0.000510213 +EDGE_SE3:QUAT 197 829 -4.08733 2.41175 0.108185 -0.00401917 -0.00932946 0.999945 0.00250388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000149206 0.0160788 3.99991 0.0373994 0.000439389 +EDGE_SE3:QUAT 830 831 4.10624 -0.105339 0.0260772 0.00497753 -0.00605341 -0.000637425 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -0.000121014 -0.0483936 3.99985 1.9798e-05 4.00058 +EDGE_SE3:QUAT 194 830 4.28667 2.42604 0.0709239 0.00440524 0.00757688 -0.999607 0.0266365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000131829 0.017642 4.00012 0.0293184 0.00313092 +EDGE_SE3:QUAT 195 830 0.272125 2.36216 0.0680465 -0.00765447 -0.00797701 0.999936 0.00246012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.00024659 0.0306202 4.00068 0.0320674 0.000515632 +EDGE_SE3:QUAT 196 830 -4.05349 2.44625 0.0499342 -0.0133366 -0.0103315 0.999844 0.00524735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9993 0.000570072 0.0533529 4.00238 0.0419215 0.00126086 +EDGE_SE3:QUAT 831 832 4.06833 -0.0900735 0.0180137 0.00274889 -0.00946074 0.00180669 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0014 -0.000100377 -0.0757681 3.99964 -6.2612e-05 4.00142 +EDGE_SE3:QUAT 193 831 3.92643 2.70697 0.0520687 0.00450555 0.00401124 -0.992422 0.122731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 1.17335e-05 0.0184838 4.00036 0.0110881 0.0603698 +EDGE_SE3:QUAT 194 831 0.184354 2.32746 0.0611647 -0.00157339 0.00230871 -0.999655 0.0261347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.48115e-05 -0.00629974 4.00001 0.00954792 0.00276482 +EDGE_SE3:QUAT 195 831 -3.8097 2.48937 0.0360366 -0.00131675 -0.00277609 0.999991 0.00299267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.45598e-05 0.00526714 4 0.0111357 7.37612e-05 +EDGE_SE3:QUAT 832 833 4.2276 -0.0775346 0.038994 0.000142105 -0.0142965 0.00573544 0.999881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00327 2.00141e-05 -0.114458 3.99918 -0.000328244 4.00314 +EDGE_SE3:QUAT 130 832 3.32247 -5.9231 0.0835534 -0.0133876 0.00792299 0.715365 0.698577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00151 0.00226287 0.0973945 4.00117 0.0378131 1.95524 +EDGE_SE3:QUAT 131 832 -1.02748 -5.85871 0.0735592 -0.0140891 0.007958 0.705223 0.708801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0017 0.00238849 0.102452 4.00113 0.0399151 2.01314 +EDGE_SE3:QUAT 191 832 6.06787 4.2187 0.116813 0.0143897 0.0111568 -0.863837 0.503442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -0.00274136 0.0863583 4.0037 -0.0243307 1.01616 +EDGE_SE3:QUAT 192 832 3.38301 2.32621 0.0355857 0.00859435 0.00318016 -0.952294 0.305046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000474737 0.0395545 4.00119 -0.00916887 0.372655 +EDGE_SE3:QUAT 193 832 -0.0211858 1.79323 0.0321725 -0.00429209 0.000277221 -0.992186 0.124691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -5.70934e-05 -0.0175598 4.00027 0.00528156 0.0622769 +EDGE_SE3:QUAT 194 832 -3.86538 2.21534 0.0919088 -0.0109615 -0.000979984 -0.999547 0.0280283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -3.80401e-05 -0.043895 4.00193 -0.00145684 0.00362501 +EDGE_SE3:QUAT 833 834 4.12002 -0.0704803 0.0334555 -0.00340933 -0.00524291 0.00441354 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 7.4004e-05 -0.0417647 3.99989 -9.42916e-05 4.00036 +EDGE_SE3:QUAT 78 833 -2.19814 5.88858 0.0915899 0.0066864 0.0110419 -0.8532 0.521424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000982558 0.0477527 4.00153 -0.00312787 1.08828 +EDGE_SE3:QUAT 130 833 3.28812 -1.69224 -0.003762 -0.00271384 -0.00174291 0.719555 0.694428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.38509e-05 0.0106753 3.99997 0.00798428 1.92898 +EDGE_SE3:QUAT 131 833 -0.919627 -1.64057 -0.0158754 -0.00371151 -0.00162709 0.709432 0.704762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -6.1869e-06 0.0164387 3.99996 0.0105624 1.98689 +EDGE_SE3:QUAT 132 833 -5.1952 -1.60328 -0.0334553 0.000828116 -0.00454481 0.711221 0.702953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 0.000128647 -0.0173139 4.00011 -0.00220519 1.97669 +EDGE_SE3:QUAT 191 833 3.92483 0.580541 0.00694085 0.00236208 0.00361822 -0.860926 0.508712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000110759 0.0161552 4.00018 -0.00111465 1.03524 +EDGE_SE3:QUAT 192 833 -0.0818869 -0.0512596 -0.00642564 -0.00482149 -0.00157811 -0.950601 0.310375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000151824 -0.0222434 4.00036 0.0059752 0.385472 +EDGE_SE3:QUAT 193 833 -4.12147 0.838887 0.10418 -0.0183646 -0.00186746 -0.991287 0.130416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99876 -0.000920096 -0.0753339 4.00533 0.0117118 0.0695102 +EDGE_SE3:QUAT 834 835 4.12927 -0.0678925 0.0291991 -0.00222168 -0.0161033 0.00269435 0.999864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00413 0.00016029 -0.128869 3.99896 -0.000187881 4.00412 +EDGE_SE3:QUAT 76 834 7.29487 1.22957 0.171626 0.0226266 0.00473532 -0.999663 0.0118043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99793 0.000287462 0.0905036 4.00817 0.0168441 0.00267718 +EDGE_SE3:QUAT 77 834 2.23227 2.94708 0.0454551 0.00538533 0.0117872 -0.976379 0.215675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.00012699 0.0239361 4.00064 0.0329054 0.186509 +EDGE_SE3:QUAT 78 834 -4.12448 2.25101 0.0445936 0.000782698 0.0117785 -0.850769 0.525408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -0.000136821 0.0177985 4.00046 0.015573 1.10451 +EDGE_SE3:QUAT 130 834 3.21333 2.41162 0.0228564 -0.00168008 -0.00750866 0.722415 0.691417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.68071e-05 -0.0103579 4.00012 0.00580161 1.91238 +EDGE_SE3:QUAT 131 834 -0.889028 2.48094 0.00786002 -0.00259907 -0.00816793 0.712646 0.701471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 3.1571e-05 -0.00785361 4.00009 0.00777684 1.96842 +EDGE_SE3:QUAT 132 834 -5.17278 2.51728 0.0306929 0.00234667 -0.0109502 0.713925 0.700132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 0.000791952 -0.04334 4.00069 -0.00610007 1.96146 +EDGE_SE3:QUAT 190 834 6.86912 -1.48382 0.0121838 0.000981702 0.00563604 -0.741431 0.671004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -0.000171392 0.0191554 4.00018 -0.00123511 1.80114 +EDGE_SE3:QUAT 191 834 1.88369 -2.97787 0.0125916 -0.00385167 0.00387665 -0.85883 0.512231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.07688e-05 -0.0160075 3.99991 0.0179708 1.0497 +EDGE_SE3:QUAT 192 834 -3.4281 -2.43137 0.0736166 -0.0108222 -8.5675e-05 -0.949207 0.314465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.00073033 -0.049248 4.00137 0.0242887 0.396352 +EDGE_SE3:QUAT 835 836 4.02983 -0.0479212 0.0371766 -0.00581254 0.0266477 0.00229388 0.999625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01127 -0.000587053 0.213862 3.99715 0.000147665 4.01138 +EDGE_SE3:QUAT 75 835 7.18098 1.56744 -0.211383 -0.0235857 0.00776274 -0.998839 0.0412787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99793 -0.00124866 -0.0945745 4.00827 0.0388131 0.00943244 +EDGE_SE3:QUAT 76 835 3.18095 1.18889 0.0151199 0.00638912 0.00661914 -0.999849 0.0147325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000159391 0.0255659 4.00051 0.0257147 0.00119695 +EDGE_SE3:QUAT 77 835 -1.5271 1.27512 0.00691739 -0.010453 0.0104127 -0.975796 0.218184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000493011 -0.0438376 4.00019 0.0541652 0.191672 +EDGE_SE3:QUAT 78 835 -6.02492 -1.3863 0.0139934 -0.0140275 0.00498705 -0.849285 0.527724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -0.000720947 -0.06837 4.00012 0.0502413 1.11602 +EDGE_SE3:QUAT 130 835 3.08934 6.51943 0.0879414 0.00803676 -0.0201758 0.724213 0.689234 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00127 0.00369054 -0.0983157 4.00308 -0.0204674 1.90359 +EDGE_SE3:QUAT 131 835 -0.883904 6.59463 0.071411 0.00720678 -0.0207719 0.71449 0.6993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00128 0.00366527 -0.0976341 4.00299 -0.0194213 1.9595 +EDGE_SE3:QUAT 191 835 -0.147514 -6.58114 0.0570676 -0.0188412 -0.00267495 -0.857226 0.514589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0008 -0.00286216 -0.101846 4.00267 0.0527995 1.06288 +EDGE_SE3:QUAT 836 837 4.25082 -0.216692 -3.44707e-05 0.0105846 0.00456335 -0.0870329 0.996139 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 0.00020249 0.0470911 3.99984 -0.00219609 3.97025 +EDGE_SE3:QUAT 74 836 6.85794 2.72555 0.124782 0.00929002 0.0120247 -0.980238 0.197236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 -1.06863e-05 0.0399969 4.0018 0.0294142 0.15626 +EDGE_SE3:QUAT 75 836 3.168 1.31656 0.0164355 0.00278807 0.0148647 -0.998952 0.0431884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000228471 0.0111973 3.99934 0.058218 0.00834147 +EDGE_SE3:QUAT 76 836 -0.808078 1.12541 0.000845541 0.0329587 0.0126991 -0.999237 0.016644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99556 0.00127793 0.131837 4.01711 0.0466463 0.00600024 +EDGE_SE3:QUAT 77 836 -5.16665 -0.362095 0.114152 0.0139022 0.0216125 -0.975126 0.220159 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99835 3.49463e-05 0.0613223 4.00438 0.0529337 0.195648 +EDGE_SE3:QUAT 837 838 3.85863 -1.29185 0.0720122 0.0113504 -0.0302051 -0.345677 0.937799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0052 -0.00486899 -0.156323 4.00018 0.0219118 3.52775 +EDGE_SE3:QUAT 73 837 6.35663 3.06052 0.1809 0.0324882 0.0144829 -0.950572 0.30846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99706 -0.00691502 0.150543 4.01797 -0.0282801 0.386938 +EDGE_SE3:QUAT 74 837 2.87906 1.29154 0.0379981 0.0148408 0.00312692 -0.993696 0.111081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 -0.000416368 0.0604793 4.0036 -0.000907748 0.050282 +EDGE_SE3:QUAT 75 837 -1.06448 1.1401 0.013064 -0.00616855 -0.00444303 0.999037 0.0432135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000138972 0.024741 4.00047 0.0198214 0.0077213 +EDGE_SE3:QUAT 76 837 -5.03651 1.18354 -0.255892 -0.0360271 -0.00508586 0.996848 0.0705043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99522 0.00286226 0.145126 4.01981 0.0406266 0.02559 +EDGE_SE3:QUAT 838 839 4.02785 -1.34024 -0.0220607 -0.00215793 -0.00207359 -0.276982 0.960871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -2.01689e-05 -0.021523 3.99997 0.00321741 3.69324 +EDGE_SE3:QUAT 72 838 5.60218 3.36174 0.0282663 0.0034193 0.00229224 -0.986373 0.164476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.96479e-05 0.0143023 4.00021 0.00417757 0.108266 +EDGE_SE3:QUAT 73 838 2.5064 1.84725 -0.00751082 -0.000374068 -0.00474635 0.999213 0.0393798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.8779e-09 0.00149745 3.99991 0.0190293 0.00629431 +EDGE_SE3:QUAT 74 838 -1.15954 1.70543 0.00591303 0.0156096 0.00669901 0.970748 0.239501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.00124911 -0.0668668 4.00207 -0.0512725 0.231283 +EDGE_SE3:QUAT 75 838 -4.7837 2.71825 0.0635151 0.026155 0.00363397 0.922166 0.385892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 0.00428629 -0.123757 4.00524 -0.0783489 0.601422 +EDGE_SE3:QUAT 839 840 4.08535 -0.672195 -0.0134806 0.000938385 0.00267718 -0.110197 0.993906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -9.6804e-06 0.02226 3.99997 -0.00124197 3.95155 +EDGE_SE3:QUAT 71 839 4.78979 3.92158 0.0196122 0.00105102 0.00540852 -0.999835 0.0173164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.6216e-05 0.0042064 3.99991 0.0214722 0.00131915 +EDGE_SE3:QUAT 72 839 1.34963 3.31552 -0.0233676 -0.000119582 -0.004893 0.993316 0.115325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.8886e-05 0.000427651 3.99991 0.0190329 0.0532912 +EDGE_SE3:QUAT 73 839 -1.39721 3.50026 -0.0151987 0.00264658 -0.00657588 0.949137 0.314783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 1.09937e-05 -0.0136797 4.00025 0.0140154 0.396469 +EDGE_SE3:QUAT 74 839 -4.11702 4.77545 0.0703395 0.0146672 0.00830978 0.866263 0.499304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 0.000517577 -0.0679272 3.99974 -0.0584187 0.999507 +EDGE_SE3:QUAT 840 841 4.31813 -0.126125 -0.00401007 0.000437427 0.000873152 0.000302265 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.53284e-06 0.00698365 4 1.06338e-06 4.00001 +EDGE_SE3:QUAT 70 840 4.66117 4.58461 0.0260482 -0.00155216 -0.00185781 0.999158 0.0409619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.24643e-05 0.00622328 4.00002 0.00790794 0.00673687 +EDGE_SE3:QUAT 71 840 0.687404 4.43436 0.00568535 -0.00318476 -0.00416132 0.995653 0.0929931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.5638e-05 0.0128769 4.00004 0.0186359 0.0347201 +EDGE_SE3:QUAT 72 840 -2.45886 4.90305 -0.0238914 -0.00252582 -0.00361935 0.974532 0.224205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.1553e-05 0.0105098 3.99997 0.0169931 0.201175 +EDGE_SE3:QUAT 841 842 4.17739 -0.0826102 0.0071524 0.000201619 0.00128309 0.00829728 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.35877e-06 0.0102436 3.99999 4.24765e-05 3.99975 +EDGE_SE3:QUAT 69 841 4.50106 5.01576 0.0740948 -0.00483144 -0.00266304 0.999642 0.0261747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.40829e-05 0.0193453 4.00033 0.0116463 0.002868 +EDGE_SE3:QUAT 70 841 0.376633 5.05623 0.0175337 -0.00245482 -0.00145156 0.999157 0.040941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.90909e-05 0.00984317 4.00008 0.0065848 0.00673978 +EDGE_SE3:QUAT 71 841 -3.50031 5.34695 -0.0136451 -0.00446898 -0.00416445 0.995668 0.0927824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.56874e-05 0.0180793 4.00017 0.0195905 0.0346132 +EDGE_SE3:QUAT 842 843 4.58764 -0.0526285 0.00250899 0.00125344 -0.00120983 0.0136326 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.74034e-06 -0.00988096 3.99999 -6.77668e-05 3.99928 +EDGE_SE3:QUAT 68 842 4.51071 5.16716 0.0836828 -0.00736837 -0.0027323 0.999604 0.0270308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000113221 0.0295051 4.00081 0.0125052 0.00317957 +EDGE_SE3:QUAT 69 842 0.337438 5.31858 0.0385269 -0.00631681 -0.00182927 0.999823 0.0176328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 6.24239e-05 0.0252786 4.00061 0.00820401 0.0014203 +EDGE_SE3:QUAT 70 842 -3.74161 5.4786 -0.00125694 -0.00393269 -0.000796841 0.999468 0.0323618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 2.41542e-05 0.0157552 4.00024 0.00419648 0.00425567 +EDGE_SE3:QUAT 843 844 4.63795 -0.0280033 0.00754489 -0.00342931 0.000130958 0.0145016 0.999889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -3.14736e-06 0.00164399 4 1.33588e-05 3.99916 +EDGE_SE3:QUAT 67 843 4.47047 5.39994 0.0587703 -0.00345823 -0.00176354 0.999946 0.00959492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.68779e-05 0.0138348 4.00018 0.00731844 0.000429496 +EDGE_SE3:QUAT 68 843 -0.044528 5.46405 0.0257936 -0.00630432 -0.00158376 0.999884 0.0137701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 5.26954e-05 0.0252241 4.00062 0.00702796 0.00092991 +EDGE_SE3:QUAT 69 843 -4.2229 5.5251 -0.0151334 -0.00525557 -0.000539666 0.999978 0.00408331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 1.4044e-05 0.0210225 4.00044 0.00233061 0.000178543 +EDGE_SE3:QUAT 844 845 4.03172 -0.065617 0.00568018 0.0011641 -0.00114254 0.0124615 0.999921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.05169e-06 -0.00931226 3.99999 -5.83427e-05 3.9994 +EDGE_SE3:QUAT 66 844 4.38375 5.4447 0.0735966 0.0035371 0.00653771 -0.999908 0.0113692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.27887e-05 0.014152 4.00004 0.0258221 0.000733825 +EDGE_SE3:QUAT 67 844 -0.120802 5.518 0.0330545 0.00362021 0.00469188 -0.99997 0.00499825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.72331e-05 0.0144818 4.00013 0.0186228 0.000239061 +EDGE_SE3:QUAT 68 844 -4.64814 5.632 -0.0171268 0.00721204 0.00482804 -0.999962 0.00115607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000138145 0.0288485 4.00074 0.0192507 0.000306036 +EDGE_SE3:QUAT 845 846 4.35191 -0.0623513 0.00219813 0.00323861 0.00230669 0.0115444 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.03254e-05 0.0180013 3.99998 0.00010344 3.99955 +EDGE_SE3:QUAT 65 845 4.9915 5.33821 0.0786279 0.00384633 0.00592732 -0.999504 0.0307041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.75454e-05 0.015409 4.00013 0.0227112 0.00395946 +EDGE_SE3:QUAT 66 845 0.376381 5.40982 0.0550908 0.00249283 0.00494052 -0.99969 0.0242563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.9913e-05 0.00998097 4.00002 0.0192501 0.00247109 +EDGE_SE3:QUAT 67 845 -4.12009 5.5373 0.0251162 0.00308223 0.00346427 -0.999836 0.017506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.01956e-05 0.0123349 4.00011 0.0134156 0.00130889 +EDGE_SE3:QUAT 846 847 4.04694 -0.0875118 0.010531 0.000955872 -0.00200323 0.00346072 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -7.35027e-06 -0.0160654 3.99998 -2.77305e-05 4.00002 +EDGE_SE3:QUAT 64 846 5.15299 5.04223 0.086973 0.00924491 0.00312929 -0.998885 0.046193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 2.10826e-05 0.0370986 4.00138 0.00904524 0.00890054 +EDGE_SE3:QUAT 65 846 0.675132 5.1343 0.0456522 0.00626091 0.0025713 -0.999088 0.0421475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 2.52858e-05 0.0251114 4.00063 0.0081339 0.00728018 +EDGE_SE3:QUAT 66 846 -3.97938 5.2645 0.037689 0.00510179 0.00201142 -0.999355 0.0354778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 1.9265e-05 0.0204461 4.00042 0.0065751 0.00515017 +EDGE_SE3:QUAT 847 848 4.08011 -0.117077 0.0281198 0.00150888 -0.00796831 -0.00058775 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -4.90203e-05 -0.0637498 3.99975 2.10453e-05 4.00101 +EDGE_SE3:QUAT 63 847 5.47897 4.67926 0.038335 0.00748404 0.00280512 -0.998746 0.0494281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 1.76805e-05 0.0300475 4.00091 0.0082022 0.0100157 +EDGE_SE3:QUAT 64 847 1.116 4.76703 0.0269762 0.00715081 0.00226987 -0.998721 0.0499929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 3.33462e-06 0.0287117 4.00083 0.00617159 0.0102134 +EDGE_SE3:QUAT 65 847 -3.34734 4.88955 0.0069341 0.00439735 0.00159086 -0.998945 0.0456811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 6.85328e-06 0.0176454 4.00031 0.00472707 0.00843067 +EDGE_SE3:QUAT 848 849 4.50699 -0.098882 0.0198164 -0.00888709 -0.00298959 -0.00553378 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.00010853 -0.0245037 3.99996 6.63666e-05 4.00003 +EDGE_SE3:QUAT 62 848 5.90006 4.2811 0.00781962 0.00382627 -0.00571301 -0.998937 0.0455735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -8.87098e-05 0.0153491 4.00006 -0.0241268 0.00851259 +EDGE_SE3:QUAT 63 848 1.39889 4.38647 0.0112252 -0.000623737 0.000830713 -0.998783 0.0493108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.18127e-06 -0.00250324 4 0.00354813 0.00973094 +EDGE_SE3:QUAT 64 848 -2.92496 4.46579 -0.010975 -0.000394097 0.000198116 -0.998768 0.0496209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.68753e-07 -0.001582 4 0.000943647 0.00984977 +EDGE_SE3:QUAT 849 850 4.38131 -0.151124 0.00838786 -0.00521367 -0.00516263 -0.0126645 0.999893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000102078 -0.0420858 3.99989 0.000264787 3.9998 +EDGE_SE3:QUAT 61 849 5.97808 3.92264 0.0133476 0.00552938 -0.00145851 -0.999058 0.0430081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -6.20483e-05 0.0221777 4.00046 -0.00770733 0.00753684 +EDGE_SE3:QUAT 62 849 1.41477 3.9473 -0.008259 0.000489554 0.00297529 -0.999188 0.0401771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.27017e-06 0.00196453 3.99997 0.011696 0.00649203 +EDGE_SE3:QUAT 63 849 -3.04768 4.02854 0.0372392 -0.00377636 0.00970583 -0.998978 0.0439768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000124217 -0.0151446 3.99978 0.0399621 0.00819325 +EDGE_SE3:QUAT 850 851 4.08192 -0.0821783 0.0208927 -0.00346735 0.00591712 0.00243643 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -8.02844e-05 0.0474429 3.99986 5.49338e-05 4.00054 +EDGE_SE3:QUAT 60 850 6.20811 3.64508 -0.0294413 -0.000599401 0.00368686 -0.999262 0.03823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.83184e-06 -0.00240124 3.99995 0.0148765 0.005903 +EDGE_SE3:QUAT 61 850 1.63317 3.6745 -0.0283364 9.7025e-05 0.00346679 -0.99953 0.0304671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.23573e-06 0.000389441 3.99995 0.0138113 0.00376075 +EDGE_SE3:QUAT 62 850 -2.90672 3.74282 -0.00350598 -0.0046822 0.00772154 -0.99958 0.0275217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000144262 -0.0187504 4.00007 0.0318603 0.00337167 +EDGE_SE3:QUAT 851 852 4.08789 -0.0419192 0.0383314 -0.00408415 -0.00107033 0.00286104 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.71798e-05 -0.00842212 4 -1.20906e-05 3.99998 +EDGE_SE3:QUAT 59 851 6.09143 3.3897 0.0137291 0.00609543 0.00560283 -0.998832 0.0475954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.0001013 0.0244694 4.00054 0.0199729 0.00931133 +EDGE_SE3:QUAT 60 851 2.14466 3.41154 -0.00442059 0.00549983 0.00735435 -0.999142 0.0403849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000145755 0.0220579 4.00035 0.027528 0.00683538 +EDGE_SE3:QUAT 61 851 -2.41113 3.50853 -0.0145453 0.00620026 0.00777728 -0.99941 0.0328876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000175197 0.0248447 4.00045 0.0294014 0.0046972 +EDGE_SE3:QUAT 852 853 4.30484 -0.218768 0.0142475 -0.000311525 0.0047001 -0.0509358 0.998691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -3.24567e-05 0.0372673 3.99991 -0.000946641 3.98997 +EDGE_SE3:QUAT 58 852 6.75715 3.02035 -0.00845353 0.000282039 0.00868119 -0.998342 0.0568951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.29812e-05 0.00114682 3.99971 0.034315 0.0132439 +EDGE_SE3:QUAT 59 852 2.02296 3.05625 0.0025475 0.00486132 0.00965547 -0.998678 0.0502624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000188921 0.0195306 4.00012 0.0364326 0.0105336 +EDGE_SE3:QUAT 60 852 -1.90998 3.13598 -0.0103891 0.00445841 0.011699 -0.998978 0.0434313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000228883 0.017895 3.99989 0.0450325 0.00813333 +EDGE_SE3:QUAT 61 852 -6.44992 3.29091 -0.0189031 0.00523795 0.0116724 -0.999276 0.0358256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000254888 0.021 4 0.0450456 0.00575224 +EDGE_SE3:QUAT 853 854 4.03928 -0.508772 0.0209688 -0.00447616 0.00220941 -0.149956 0.98868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -2.08666e-05 0.00914803 4 -0.000469698 3.91007 +EDGE_SE3:QUAT 58 853 2.44003 2.74807 0.00216724 0.00444876 0.00915985 -0.999933 0.00548712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000164018 0.0177979 3.99999 0.0364439 0.000531666 +EDGE_SE3:QUAT 59 853 -2.29599 2.82346 -0.02355 -0.00925432 -0.0106424 0.9999 0.000772766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000395218 0.0370221 4.00091 0.0426443 0.000799529 +EDGE_SE3:QUAT 60 853 -6.21594 2.97932 -0.0238127 -0.00882553 -0.0125014 0.999852 0.00786061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000446083 0.0353126 4.00058 0.0505701 0.00119812 +EDGE_SE3:QUAT 854 855 4.00809 -1.26006 -0.0175526 -0.00382685 -0.00955126 -0.31201 0.950023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0015 -0.000603092 -0.0789542 3.99977 0.0124398 3.61215 +EDGE_SE3:QUAT 57 854 3.00789 3.10298 0.0229973 -0.00401365 -0.0147655 0.99011 0.13946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.48339e-06 0.0161976 3.99912 0.0605938 0.0787979 +EDGE_SE3:QUAT 58 854 -1.59545 3.20964 0.00480901 -0.00552288 -0.014428 0.98943 0.144189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.84956e-05 0.0224281 3.99923 0.0609678 0.0842364 +EDGE_SE3:QUAT 59 854 -6.32307 3.32514 -0.0549077 -0.0101382 -0.0166116 0.988448 0.150306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000492582 0.0414708 3.99946 0.0746449 0.0922243 +EDGE_SE3:QUAT 855 856 4.10631 -1.34522 -0.00417792 0.00305993 0.002168 -0.255088 0.966911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.1034e-05 0.0246399 3.99996 -0.00346412 3.73987 +EDGE_SE3:QUAT 56 855 4.02961 5.32018 0.026313 0.00393273 -0.0195976 0.899697 0.436057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99917 0.00027041 -0.0325242 4.00157 0.0326181 0.761416 +EDGE_SE3:QUAT 57 855 -0.471325 5.40866 0.027856 0.00938646 -0.0196405 0.897125 0.44124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9991 0.00146099 -0.0602811 4.00368 0.0163578 0.780117 +EDGE_SE3:QUAT 856 857 4.15353 -0.435041 -0.00207619 0.00512419 0.00305433 -0.0586403 0.998261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 5.82602e-05 0.0279065 3.99995 -0.000850898 3.98644 +EDGE_SE3:QUAT 857 858 4.16056 -0.0919325 0.00932026 0.000513955 1.47924e-05 0.00558011 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.86343e-08 8.39189e-05 4 2.0213e-07 3.99988 +EDGE_SE3:QUAT 858 859 4.32125 -0.0317424 0.00471605 7.28097e-05 0.000400828 0.012714 0.999919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.64906e-07 0.00319474 4 2.02841e-05 3.99936 +EDGE_SE3:QUAT 859 860 4.06521 -0.0638831 0.00267758 -0.00145315 0.00577228 0.00683185 0.999959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 -2.81943e-05 0.0462994 3.99987 0.000157176 4.00035 +EDGE_SE3:QUAT 860 861 4.28134 -0.0910898 0.00790475 0.00165047 0.000607204 0.0033806 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.96419e-06 0.00479058 4 8.07407e-06 3.99996 +EDGE_SE3:QUAT 861 862 4.28399 -0.0919243 0.010477 0.000213737 -1.32421e-05 0.0021431 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.20946e-08 -0.000111433 4 -1.21368e-07 3.99998 +EDGE_SE3:QUAT 862 863 4.31447 -0.0941592 0.0189963 -0.00029513 0.00261376 0.000760804 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.96164e-06 0.0209132 3.99997 7.90794e-06 4.00011 +EDGE_SE3:QUAT 863 864 4.46618 -0.0945651 0.00832338 -0.00234782 -0.000526301 -0.000166375 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.94883e-06 -0.00421506 4 3.35135e-07 4 +EDGE_SE3:QUAT 864 865 4.51487 -0.10119 0.01409 -0.00229142 3.8996e-05 0.000348703 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.72056e-07 0.000321554 4 5.65327e-08 4 +EDGE_SE3:QUAT 865 866 4.65404 -0.0884744 0.0135006 -0.00173072 0.00141775 -0.000607225 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.82982e-06 0.0113294 3.99999 -3.52188e-06 4.00003 +EDGE_SE3:QUAT 866 867 4.00812 -0.0845723 0.0113711 -0.00220838 -0.000255203 -0.000601985 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.27685e-06 -0.00205756 4 6.17416e-07 4 +EDGE_SE3:QUAT 867 868 4.08697 -0.0776853 0.0199088 -0.00321773 0.00287464 -0.000263232 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -3.70331e-05 0.0229872 3.99997 -3.66302e-06 4.00013 +EDGE_SE3:QUAT 868 869 4.03257 -0.0904844 0.0149693 -0.00054024 -0.000382589 -0.000471139 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.26202e-07 -0.00306376 4 7.20069e-07 4 +EDGE_SE3:QUAT 869 870 4.15732 -0.10006 0.0148907 0.00141299 0.001492 -0.000576357 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 8.4113e-06 0.0119458 3.99999 -3.36795e-06 4.00003 +EDGE_SE3:QUAT 870 871 4.04353 -0.104246 0.0104148 -0.000141946 -0.000245923 -0.00055385 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.38916e-07 -0.00196833 4 5.44961e-07 4 +EDGE_SE3:QUAT 871 872 4.21714 -0.0985864 0.0229087 0.000508508 0.00179126 0.000733751 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 3.69859e-06 0.0143257 3.99999 5.29452e-06 4.00005 +EDGE_SE3:QUAT 872 873 4.07549 -0.0817345 0.0228059 -0.000967299 0.000318321 0.00112709 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.23732e-06 0.00255964 4 1.44256e-06 4 +EDGE_SE3:QUAT 873 874 4.10172 -0.112811 0.0227499 0.0021401 1.83612e-05 -0.00228094 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.40718e-07 0.000205464 4 -2.56565e-07 3.99998 +EDGE_SE3:QUAT 874 875 4.4767 -0.123278 0.0207543 0.000733279 0.00346053 -0.00482261 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 8.78274e-06 0.0277269 3.99995 -6.66885e-05 4.0001 +EDGE_SE3:QUAT 875 876 4.32122 -0.108273 0.0258286 -0.00172 -0.000408231 -0.00454892 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.89714e-06 -0.00335962 4 7.70524e-06 3.99992 +EDGE_SE3:QUAT 876 877 4.131 -0.118604 0.0186119 -0.00137862 0.000834752 -0.00517568 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.60915e-06 0.00659212 4 -1.7008e-05 3.9999 +EDGE_SE3:QUAT 877 878 4.39439 -0.048008 0.0227832 -0.00117622 0.00122377 0.0297247 0.999557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.93753e-06 0.0101966 3.99999 0.000153516 3.99649 +EDGE_SE3:QUAT 878 879 4.1543 0.277519 0.0314847 -0.000815721 -0.00340164 0.110365 0.993885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 3.8377e-05 -0.0256467 3.99996 -0.00138652 3.95144 +EDGE_SE3:QUAT 879 880 4.1973 0.687599 0.00927741 0.000133331 -0.00104311 0.20361 0.979052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.69166e-06 -0.00814815 4 -0.000822411 3.83419 +EDGE_SE3:QUAT 880 881 4.07727 0.789064 -0.0171632 -0.00196127 0.00423606 0.222035 0.975028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 7.34475e-05 0.0364702 3.99993 0.00414568 3.80313 +EDGE_SE3:QUAT 881 882 4.2634 0.846943 -0.00251045 0.000225241 -0.000254796 0.200535 0.979686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.34989e-07 -0.00244415 4 -0.000258935 3.83914 +EDGE_SE3:QUAT 882 883 4.27846 0.315445 -0.00435628 -0.00461802 0.000605188 0.0711488 0.997455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -2.1521e-05 0.00873412 3.99999 0.000356921 3.97977 +EDGE_SE3:QUAT 883 884 4.34621 -0.0454852 0.0043852 -0.00104767 -0.00198632 0.00723497 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 8.939e-06 -0.0157985 3.99998 -5.71403e-05 3.99985 +EDGE_SE3:QUAT 884 885 4.02657 -0.0924665 0.011851 -0.00341344 0.000604275 -0.0172456 0.999845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -6.75691e-06 0.00412571 4 -3.35619e-05 3.99881 +EDGE_SE3:QUAT 885 886 4.09672 -0.30704 0.0151775 0.00300451 0.00240973 -0.0615879 0.998094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.30601e-05 0.0213834 3.99997 -0.000679694 3.98494 +EDGE_SE3:QUAT 886 887 4.11296 -0.424593 0.0131912 -0.002278 0.00110303 -0.111235 0.993791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.89817e-06 0.00564525 4 -0.000254579 3.95051 +EDGE_SE3:QUAT 887 888 4.0071 -0.875764 0.0199326 0.00318539 0.00577233 -0.22286 0.974828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -0.000130088 0.0510254 3.99986 -0.0058685 3.80198 +EDGE_SE3:QUAT 888 889 3.95583 -0.896908 0.00934966 -0.00859108 -0.00468287 -0.22578 0.974129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 3.19481e-05 -0.0571276 3.99978 0.00720526 3.7969 +EDGE_SE3:QUAT 889 890 3.99551 -0.809778 0.00433068 0.00583226 0.00346447 -0.174985 0.984548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 3.59976e-05 0.0384513 3.9999 -0.00368095 3.87789 +EDGE_SE3:QUAT 890 891 4.11494 -0.504904 -0.0349971 0.00864724 0.0220381 -0.13789 0.990165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00831 -0.00093986 0.185773 3.99794 -0.01298 3.93255 +EDGE_SE3:QUAT 891 892 3.89782 -1.23918 0.0664375 0.0055907 -0.0312754 -0.327525 0.944308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00872 -0.00582811 -0.190887 3.99956 0.0280425 3.57976 +EDGE_SE3:QUAT 892 893 4.2253 -1.37585 -0.0477131 0.00136313 0.00551426 -0.267361 0.96358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -0.000169236 0.0436392 3.99992 -0.00580685 3.71455 +EDGE_SE3:QUAT 893 894 4.33419 -0.552338 -0.0232281 0.000499023 0.00284272 -0.0750489 0.997176 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -9.09369e-06 0.0229983 3.99997 -0.000866182 3.9776 +EDGE_SE3:QUAT 894 895 4.53302 -0.131557 -0.00907511 -0.00245633 -0.000682457 -0.00299148 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.81531e-06 -0.00554772 4 8.31375e-06 3.99997 +EDGE_SE3:QUAT 895 896 4.34249 -0.0862229 0.00523659 0.000285477 0.000570287 0.00355106 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.76488e-07 0.00455005 4 8.07376e-06 3.99995 +EDGE_SE3:QUAT 896 897 4.59068 -0.0773496 0.000633378 0.00119757 0.00120879 0.00282108 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 5.85637e-06 0.00962968 3.99999 1.36059e-05 3.99999 +EDGE_SE3:QUAT 897 898 4.15504 -0.0987888 0.0132945 -0.00169712 -7.5203e-05 -0.000583683 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.2388e-07 -0.000613508 4 1.79966e-07 4 +EDGE_SE3:QUAT 898 899 4.87142 -0.115228 0.00796465 0.00283216 0.00219523 -0.000871959 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.48251e-05 0.0175916 3.99998 -7.34581e-06 4.00007 +EDGE_SE3:QUAT 899 900 4.17334 -0.0984728 0.0112646 0.0009807 -0.00178382 -0.000566113 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -7.03671e-06 -0.014264 3.99999 4.11187e-06 4.00005 +EDGE_SE3:QUAT 900 901 4.28517 -0.100476 0.00420559 -0.00171488 0.000589991 -0.00115439 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.02945e-06 0.00469615 4 -2.72024e-06 4 +EDGE_SE3:QUAT 901 902 4.29673 -0.0971427 0.0044557 0.00174346 0.000429922 7.34935e-05 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.99674e-06 0.00343782 4 1.34039e-07 4 +EDGE_SE3:QUAT 902 903 4.31643 -0.113917 0.0183841 -0.000776576 0.00207047 -0.000878647 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -6.51796e-06 0.0165558 3.99998 -7.35229e-06 4.00007 +EDGE_SE3:QUAT 903 904 4.22416 -0.101976 0.0155672 0.000363028 -0.000519423 -0.000503976 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.56992e-07 -0.00415319 4 1.04872e-06 4 +EDGE_SE3:QUAT 904 905 4.40351 -0.0964668 0.012228 0.00261439 0.00202764 0.00614059 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.14624e-05 0.0160276 3.99998 4.92665e-05 3.99991 +EDGE_SE3:QUAT 905 906 4.14127 0.00953035 0.0304392 -0.00498921 -0.00191091 0.0187174 0.999811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.58395e-05 -0.0141585 3.99999 -0.000129375 3.99865 +EDGE_SE3:QUAT 906 907 4.05082 -0.0483339 0.0189613 0.00122527 0.00182069 0.0106055 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 9.62395e-06 0.0144072 3.99999 7.62167e-05 3.9996 +EDGE_SE3:QUAT 907 908 4.45877 -0.066805 0.0207838 -0.000868032 -0.00137323 0.00495997 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.96084e-06 -0.0109338 3.99999 -2.71121e-05 3.99993 +EDGE_SE3:QUAT 908 909 4.25289 -0.103708 0.0230083 0.00223864 0.000128506 -0.00299465 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.26941e-06 0.00110847 4 -1.69889e-06 3.99996 +EDGE_SE3:QUAT 909 910 4.22872 -0.15172 0.0209257 0.00203584 0.00115359 -0.0151966 0.999882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 9.37771e-06 0.00959673 3.99999 -7.37829e-05 3.9991 +EDGE_SE3:QUAT 910 911 4.13459 -0.221377 0.0210761 -0.00285579 0.00232122 -0.0465928 0.998907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.85887e-05 0.0169149 3.99998 -0.000381526 3.99139 +EDGE_SE3:QUAT 911 912 4.16791 -0.641565 0.00626144 0.00578238 0.00245487 -0.188412 0.98207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 4.26563e-05 0.0313676 3.99993 -0.00333007 3.85825 +EDGE_SE3:QUAT 912 913 3.83858 -1.4093 0.140941 -0.021317 -0.0221776 -0.374054 0.926896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01124 -0.00452721 -0.228946 3.99804 0.0461013 3.45339 +EDGE_SE3:QUAT 913 914 3.92169 -0.894126 -0.0244854 0.00277452 0.0102113 -0.174471 0.984606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00172 -0.000343431 0.0837122 3.99961 -0.00736174 3.87999 +EDGE_SE3:QUAT 914 915 4.36456 -0.230695 -0.0117789 0.00392756 0.00179346 -0.0162405 0.999859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.88061e-05 0.0151071 3.99999 -0.000124405 3.999 +EDGE_SE3:QUAT 915 916 4.16986 -0.0450762 0.000472396 8.93685e-05 -0.000167382 0.0101558 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.3557e-08 -0.00134974 4 -6.8719e-06 3.99959 +EDGE_SE3:QUAT 916 917 4.04059 -0.0791725 0.00913963 0.00246378 0.0052227 0.00105762 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 5.21296e-05 0.0417539 3.99989 2.36917e-05 4.00043 +EDGE_SE3:QUAT 917 918 4.00215 -0.0875482 -0.0218876 -0.00123306 0.00600811 0.000658964 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 -2.90851e-05 0.0480805 3.99986 1.478e-05 4.00058 +EDGE_SE3:QUAT 918 919 4.03593 -0.0860442 0.00982223 0.000473506 -0.000605213 0.00128232 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.13729e-06 -0.00484899 4 -3.10637e-06 4 +EDGE_SE3:QUAT 919 920 4.04693 -0.0695464 0.00786655 0.000725122 -0.0272282 0.00112342 0.999628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01189 -5.97396e-05 -0.218401 3.99703 -0.000110686 4.01188 +EDGE_SE3:QUAT 920 921 4.26245 -0.0840348 -0.0116083 0.000848233 0.000463763 0.0012876 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.57271e-06 0.00369699 4 2.38166e-06 4 +EDGE_SE3:QUAT 921 922 4.27189 -0.0996801 0.00190379 -0.00179773 -0.00266292 0.00109736 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.93087e-05 -0.0212801 3.99997 -1.19779e-05 4.00011 +EDGE_SE3:QUAT 922 923 4.36016 -0.101874 -0.0397395 0.0046353 0.00506399 0.000831633 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 9.42899e-05 0.0404679 3.9999 1.96731e-05 4.00041 +EDGE_SE3:QUAT 923 924 4.28292 -0.094374 -0.00021056 0.000596256 0.00121615 0.00107533 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.93567e-06 0.00972155 3.99999 5.24679e-06 4.00002 +EDGE_SE3:QUAT 924 925 4.33052 -0.0845048 -0.00686642 -0.000217084 0.000621199 0.000120266 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.38344e-07 0.00496991 4 2.96853e-07 4.00001 +EDGE_SE3:QUAT 925 926 4.33424 -0.0928454 0.00140012 -0.000630018 -0.000420177 0.000742075 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.05966e-06 -0.0033558 4 -1.2471e-06 4 +EDGE_SE3:QUAT 926 927 4.43607 -0.0646881 0.00174979 -0.000704051 0.00207134 0.00470098 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -5.36618e-06 0.0166101 3.99998 3.90015e-05 3.99998 +EDGE_SE3:QUAT 927 928 4.39622 -0.0953384 0.00793117 0.00027611 0.00219221 0.0015913 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.6038e-06 0.0175326 3.99998 1.39809e-05 4.00007 +EDGE_SE3:QUAT 928 929 4.42119 -0.0944377 0.00597616 -0.00233051 -0.00209653 -0.00035315 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.95229e-05 -0.0167822 3.99998 2.71795e-06 4.00007 +EDGE_SE3:QUAT 929 930 4.34385 -0.103004 -0.00428808 0.00155541 0.0021193 -0.00126769 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.30738e-05 0.0169782 3.99998 -1.0599e-05 4.00007 +EDGE_SE3:QUAT 930 931 4.29908 -0.103559 0.00448469 0.000197898 0.00170049 -0.0016108 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.23481e-06 0.0136078 3.99999 -1.09473e-05 4.00004 +EDGE_SE3:QUAT 931 932 4.18387 -0.0941878 0.0210381 4.08835e-05 0.00172398 -0.000955731 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.13776e-07 0.0137924 3.99999 -6.58829e-06 4.00004 +EDGE_SE3:QUAT 932 933 4.03311 -0.0849797 0.0281282 -0.000960158 0.00215266 -0.000160317 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -8.28474e-06 0.0172197 3.99998 -1.48709e-06 4.00007 +EDGE_SE3:QUAT 933 934 4.29797 -0.10352 0.0270454 0.00220671 -0.00103394 -0.000690639 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.11723e-06 -0.00825321 4 2.90434e-06 4.00002 +EDGE_SE3:QUAT 934 935 4.24221 -0.111502 0.0551441 -0.00103638 0.0147534 -0.00773631 0.999861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00347 -0.000101673 0.11801 3.99913 -0.000462798 4.00324 +EDGE_SE3:QUAT 935 936 4.1189 -0.16713 -0.0306703 -0.00137504 0.0134653 -0.00485509 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00289 -9.52923e-05 0.107707 3.99928 -0.000267874 4.0028 +EDGE_SE3:QUAT 936 937 4.03218 0.474784 0.00288465 0.00228886 -0.00352095 0.215642 0.976463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 4.22137e-05 -0.0319669 3.99994 -0.00358594 3.81425 +EDGE_SE3:QUAT 937 938 4.10389 1.11424 -0.00327045 -0.000271386 -0.00196987 0.290244 0.956951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.23519e-05 -0.0129181 4 -0.00172673 3.66308 +EDGE_SE3:QUAT 938 939 4.06501 0.578606 -0.00752651 0.00419617 -0.00248299 0.170635 0.985322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -1.98449e-05 -0.0274288 3.99995 -0.00255835 3.88372 +EDGE_SE3:QUAT 939 940 4.31187 0.592336 0.00718368 -2.85266e-05 0.0083954 0.173156 0.984859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 0.000276525 0.0642376 3.99978 0.00547812 3.8811 +EDGE_SE3:QUAT 940 941 3.99229 0.597057 0.0173189 -0.00286587 -0.00213851 0.180523 0.983564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.06444e-05 -0.010205 4 -0.000708822 3.86967 +EDGE_SE3:QUAT 941 942 4.28242 0.751489 0.000369747 0.00461296 -0.00482506 0.217886 0.975951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 5.73343e-05 -0.0475695 3.99986 -0.00551446 3.81067 +EDGE_SE3:QUAT 942 943 4.27176 0.836457 -0.0228871 -0.00354983 -0.000116833 0.196274 0.980543 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -1.56763e-05 0.00726494 3.99999 0.000988038 3.84592 +EDGE_SE3:QUAT 943 944 4.18136 0.326261 -0.0155087 0.0022664 -0.0122467 0.0916367 0.995715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00244 0.000224941 -0.0992741 3.9994 -0.00456665 3.96887 +EDGE_SE3:QUAT 944 945 4.49421 0.0802357 0.0136697 -0.0011595 -0.00296059 0.0251543 0.999679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.86096e-05 -0.023313 3.99997 -0.000291914 3.9976 +EDGE_SE3:QUAT 945 946 4.04264 -0.0701997 -0.0144206 0.000999937 -0.00843628 0.00497736 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00114 -2.52987e-05 -0.0675642 3.99971 -0.000166608 4.00104 +EDGE_SE3:QUAT 946 947 4.18976 -0.0725958 -0.039961 -0.00123043 0.00659505 0.00278834 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -2.95973e-05 0.0528089 3.99983 7.23907e-05 4.00067 +EDGE_SE3:QUAT 947 948 4.28875 -0.0750932 0.016896 0.00149313 0.00515745 0.00161684 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 3.18164e-05 0.0412342 3.99989 3.42882e-05 4.00041 +EDGE_SE3:QUAT 948 949 4.36939 -0.0838956 0.0357674 -0.000190004 -8.21256e-05 0.0011136 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.22741e-08 -0.000654465 4 -3.63967e-07 4 +EDGE_SE3:QUAT 949 950 4.22958 -0.0768376 0.0139182 0.000534309 -0.00541776 0.00115111 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -1.07751e-05 -0.0433538 3.99988 -2.45851e-05 4.00046 +EDGE_SE3:QUAT 950 951 4.40996 -0.0880236 -0.0460718 -0.000726125 -0.00161101 0.00131747 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.75572e-06 -0.0128767 3.99999 -8.52514e-06 4.00003 +EDGE_SE3:QUAT 951 952 3.97782 -0.0784308 -0.0233028 -0.00106763 0.00738554 0.00107727 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00087 -3.01626e-05 0.0591092 3.99978 3.04604e-05 4.00087 +EDGE_SE3:QUAT 952 953 4.27911 -0.0950736 0.0246718 0.000757953 0.00342421 0.00118833 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 1.0712e-05 0.0273839 3.99995 1.64836e-05 4.00018 +EDGE_SE3:QUAT 953 954 4.43226 -0.0882275 0.0164817 -0.00166969 -0.00271621 0.00097249 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 1.82928e-05 -0.0217106 3.99997 -1.08496e-05 4.00011 +EDGE_SE3:QUAT 954 955 4.33022 -0.0899818 -0.000491669 0.00157809 -0.00371509 -0.00552655 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -2.51646e-05 -0.029616 3.99995 8.22712e-05 4.0001 +EDGE_SE3:QUAT 955 956 4.39333 -0.159306 -0.0142584 -0.00014734 0.00118828 -0.00981195 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.03001e-06 0.00948755 3.99999 -4.65207e-05 3.99964 +EDGE_SE3:QUAT 956 957 4.23269 -0.107504 0.0171553 0.000338455 0.00316747 -0.00296166 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 3.57774e-06 0.0253524 3.99996 -3.74707e-05 4.00013 +EDGE_SE3:QUAT 957 958 4.22476 -0.0886077 0.043166 0.00138089 0.0328223 0.00707572 0.999435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01727 0.000367666 0.263431 3.9957 0.000978229 4.01707 +EDGE_SE3:QUAT 958 959 4.31718 0.113628 0.00266089 0.00151069 0.00099712 0.0813654 0.996683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.86799e-06 0.00642936 4 0.00024051 3.97353 +EDGE_SE3:QUAT 959 960 4.12817 0.566017 0.00595706 -0.000747124 -0.00859097 0.176014 0.98435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00102 0.000307007 -0.0640269 3.99979 -0.00549803 3.8771 +EDGE_SE3:QUAT 960 961 4.35145 0.807498 0.00974879 0.00292534 0.00598041 0.22701 0.97387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 0.000179994 0.036499 3.99996 0.00369923 3.79419 +EDGE_SE3:QUAT 961 962 4.11156 0.840838 0.00957946 -0.00248764 -0.00322851 0.227952 0.973664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 4.97775e-05 -0.0172722 3.99999 -0.00163144 3.79222 +EDGE_SE3:QUAT 962 963 4.17015 0.615449 -0.012891 0.00273738 0.00507876 0.186402 0.982457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 0.00012445 0.0325508 3.99996 0.00277801 3.86128 +EDGE_SE3:QUAT 963 964 4.16282 0.726317 0.00878177 -0.00595372 2.63966e-05 0.205242 0.978693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -4.75841e-05 0.0144495 3.99998 0.00198321 3.83155 +EDGE_SE3:QUAT 964 965 4.18567 0.746315 0.00912005 0.000174476 -0.00456798 0.204746 0.978804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 9.35821e-05 -0.0346891 3.99994 -0.00348563 3.83262 +EDGE_SE3:QUAT 965 966 4.18298 0.533727 0.00655021 0.0030351 -0.00275347 0.139814 0.990169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -8.05189e-06 -0.0264116 3.99995 -0.00194916 3.92198 +EDGE_SE3:QUAT 966 967 4.18778 0.344897 -0.00251911 0.000528733 -0.017998 0.0958843 0.99523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00509 0.000701155 -0.142766 3.99878 -0.00684149 3.96831 +EDGE_SE3:QUAT 967 968 4.13442 0.030668 0.010588 0.00754901 -0.00342013 0.0295955 0.999528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -0.000106982 -0.0300037 3.99994 -0.000454632 3.99672 +EDGE_SE3:QUAT 968 969 4.11483 -0.0215229 -0.0316482 -0.0140315 -0.00233261 -0.00106801 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9993 0.000132419 -0.0188355 3.99998 8.23058e-06 4.00008 +EDGE_SE3:QUAT 969 970 4.11731 -0.107634 -0.0454482 0.00588835 0.00397886 -0.00078467 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 9.36487e-05 0.0318864 3.99994 -1.02759e-05 4.00025 +EDGE_SE3:QUAT 970 971 4.52014 -0.101337 -0.00555742 0.00220851 0.00413635 -0.00175002 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 3.58971e-05 0.0331388 3.99993 -2.81066e-05 4.00026 +EDGE_SE3:QUAT 971 972 4.24676 -0.0888328 0.0303366 -0.00114552 0.00114148 -0.00133024 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.2579e-06 0.00911356 3.99999 -6.09334e-06 4.00001 +EDGE_SE3:QUAT 972 973 4.48186 -0.103733 -0.0273515 0.000111315 -0.00759041 -0.0027364 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 -7.16647e-06 -0.0607312 3.99977 8.32945e-05 4.00089 +EDGE_SE3:QUAT 973 974 4.01885 -0.118732 -0.0471174 0.000815744 0.000910915 -0.00583645 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.88555e-06 0.00734409 4 -2.14707e-05 3.99988 +EDGE_SE3:QUAT 974 975 4.05329 -0.0948463 -0.0135464 -0.000361315 0.00891031 -0.000219486 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00127 -1.33102e-05 0.0713013 3.99968 -8.52003e-06 4.00127 +EDGE_SE3:QUAT 975 976 4.0576 -0.0837619 0.0352079 -0.000383427 0.000292223 0.0020493 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.46365e-07 0.0023472 4 2.40749e-06 3.99998 +EDGE_SE3:QUAT 976 977 3.99253 -0.0869701 0.0127117 -0.000232236 -0.00393887 0.00206444 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 4.42739e-06 -0.0315067 3.99994 -3.26116e-05 4.00023 +EDGE_SE3:QUAT 977 978 4.32847 -0.0859726 -0.0214244 0.000250854 0.000153915 0.00323637 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.54626e-07 0.00122156 4 1.97159e-06 3.99996 +EDGE_SE3:QUAT 978 979 4.37035 -0.077663 0.00504423 0.000636553 0.00207902 0.00408021 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 5.70256e-06 0.0166008 3.99998 3.39133e-05 4 +EDGE_SE3:QUAT 979 980 4.13777 -0.086508 0.0425195 0.000870695 -0.00039904 0.000214848 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.39025e-06 -0.00319456 4 -3.39922e-07 4 +EDGE_SE3:QUAT 980 981 4.06241 -0.220864 0.0338047 -0.00394889 0.0202098 -0.0654559 0.997643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00615 -0.000928862 0.157753 3.9985 -0.0051766 3.98907 +EDGE_SE3:QUAT 981 982 4.08559 -0.611778 -0.0182338 -0.00773971 0.0123479 -0.162542 0.986594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00135 -0.000722996 0.0800772 3.99971 -0.00601989 3.89591 +EDGE_SE3:QUAT 982 983 4.17044 -1.00303 -0.000215718 -0.00210095 0.00340202 -0.221334 0.97519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -5.71912e-05 0.0198431 3.99999 -0.00191443 3.80414 +EDGE_SE3:QUAT 742 982 -1.05868 7.55591 0.108219 0.00311329 0.0127899 -0.847525 0.530592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000495668 0.0317775 4.00099 0.00944943 1.12658 +EDGE_SE3:QUAT 983 984 3.95444 -0.815911 0.00982375 0.00623469 0.00549157 -0.190557 0.981641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -1.87808e-05 0.055481 3.9998 -0.00565613 3.85552 +EDGE_SE3:QUAT 612 983 4.28338 -5.02234 -0.0239326 -0.00799917 -0.00486974 0.346061 0.938165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -3.83213e-05 -0.00160422 4 0.00206447 3.52093 +EDGE_SE3:QUAT 613 983 0.00942162 -4.92817 -0.0224806 -0.00948123 -0.0042052 0.344849 0.938601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000114361 0.00830409 3.99997 0.00404663 3.52429 +EDGE_SE3:QUAT 614 983 -4.215 -4.81871 -0.115951 -0.0125304 -0.0105717 0.342978 0.9392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99937 0.000163929 -0.0225481 4.00006 -1.61984e-05 3.52947 +EDGE_SE3:QUAT 740 983 5.54037 3.95745 0.0743162 0.00605539 0.0137768 -0.975508 0.219448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99954 0.000175512 0.0270703 4.00083 0.0384805 0.193227 +EDGE_SE3:QUAT 741 983 1.05327 4.30744 0.0663186 0.00233304 0.0168505 -0.962902 0.269315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000375841 0.0129269 3.99999 0.0508413 0.290894 +EDGE_SE3:QUAT 742 983 -3.76386 4.23847 0.0438303 0.00184926 0.0166727 -0.943775 0.330164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.000300944 0.0133052 4.00018 0.0448826 0.436702 +EDGE_SE3:QUAT 984 985 4.16894 -0.897394 -0.0357989 -9.57638e-05 0.010621 -0.205814 0.978533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 -0.000516155 0.0794234 3.9997 -0.00798362 3.83214 +EDGE_SE3:QUAT 613 984 3.51878 -2.98102 0.00778436 -0.00467401 0.00133467 0.159949 0.987113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.32524e-05 0.0190885 3.99997 0.00175407 3.89775 +EDGE_SE3:QUAT 614 984 -0.654005 -2.88093 -0.0346786 -0.00618258 -0.00546069 0.157777 0.98744 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000147507 -0.0305517 3.99997 -0.00206182 3.90065 +EDGE_SE3:QUAT 615 984 -4.98913 -2.77291 -0.0580566 -0.00639307 -0.00732488 0.155701 0.987756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000262717 -0.0447292 3.99992 -0.00312291 3.90352 +EDGE_SE3:QUAT 739 984 5.8525 2.81095 -0.00880547 -0.00484667 0.013505 -0.999836 0.0110763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000251375 -0.0193952 3.99961 0.0544344 0.0013257 +EDGE_SE3:QUAT 740 984 1.64887 2.97812 0.0326542 0.00997358 0.00987678 -0.999465 0.0295424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000341587 0.0399508 4.00134 0.0370855 0.00423442 +EDGE_SE3:QUAT 741 984 -2.65947 2.93363 0.0493701 0.0059141 0.0126672 -0.996615 0.0810086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.0003023 0.0239456 4.00023 0.0460409 0.0269279 +EDGE_SE3:QUAT 985 986 3.9161 -0.924123 -0.000989326 -0.00275545 0.00149719 -0.234609 0.972085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.3351e-06 0.00352948 4 -7.09171e-05 3.77984 +EDGE_SE3:QUAT 614 985 3.55187 -2.42626 -0.0226862 -0.00644929 0.00373678 -0.0487168 0.998785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.29694e-05 0.0260227 3.99996 -0.000604206 3.99068 +EDGE_SE3:QUAT 615 985 -0.771103 -2.34404 -0.0303372 -0.00623699 0.00185313 -0.0508723 0.998684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -3.28456e-05 0.0109659 3.99999 -0.000246485 3.98968 +EDGE_SE3:QUAT 616 985 -5.04522 -2.24001 -0.0409546 -0.00601132 0.00261063 -0.0526644 0.998591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -5.35299e-05 0.0170054 3.99998 -0.000414416 3.98898 +EDGE_SE3:QUAT 738 985 5.34035 3.94249 0.0164655 -0.00805234 -0.00676056 0.989483 0.144268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000314988 0.0330412 4.00046 0.0347534 0.0838372 +EDGE_SE3:QUAT 739 985 1.67561 3.59496 0.0216708 -0.00292264 -0.0123584 0.980773 0.194737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000100692 0.0116059 3.99937 0.0491856 0.152353 +EDGE_SE3:QUAT 740 985 -2.46792 3.60073 -0.0674219 -0.018566 -0.0118256 0.983871 0.17752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99943 0.0016658 0.0772081 4.00282 0.0692417 0.128802 +EDGE_SE3:QUAT 986 987 3.93533 -1.06947 -0.014313 -0.000370609 0.00110689 -0.243349 0.969938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -6.37289e-06 0.00704081 4 -0.000779554 3.76314 +EDGE_SE3:QUAT 555 986 3.21217 -4.02441 0.0201654 -0.0112412 -0.00453989 0.711228 0.702856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -1.45189e-05 0.0509771 3.99968 0.0321279 1.97723 +EDGE_SE3:QUAT 556 986 -2.78432 -4.04321 0.0528325 -0.0112666 0.000964898 0.547171 0.836945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 0.000200441 0.063751 3.99977 0.0234321 2.80342 +EDGE_SE3:QUAT 615 986 3.00733 -3.64735 -0.0291676 -0.00922467 0.00206619 -0.283429 0.958947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000114595 -0.0151162 3.99996 0.00371901 3.6787 +EDGE_SE3:QUAT 616 986 -1.2603 -3.55669 -0.0464216 -0.00904425 0.00267123 -0.285341 0.95838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 9.79391e-05 -0.0104745 3.99997 0.00309401 3.67432 +EDGE_SE3:QUAT 617 986 -5.38557 -3.58223 -0.0587906 -0.00980521 0.00289935 -0.271383 0.962417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000104619 -0.0096849 3.99997 0.00287695 3.7054 +EDGE_SE3:QUAT 738 986 1.84497 5.94051 -0.0271423 -0.00806212 -0.0107641 0.927989 0.372364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.95649e-05 0.033786 3.99945 0.0495593 0.55562 +EDGE_SE3:QUAT 739 986 -1.58489 5.93759 0.0446885 -0.00191579 -0.0150947 0.907722 0.419296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 -0.000332805 0.000498658 3.99977 0.0408371 0.703816 +EDGE_SE3:QUAT 987 988 4.13777 -0.923031 -0.00345399 0.00961777 0.0182948 -0.162953 0.986417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00596 -0.000725375 0.159257 3.9985 -0.0132871 3.90012 +EDGE_SE3:QUAT 555 987 4.23767 -0.0750642 -0.00873857 -0.010884 -0.00664619 0.51879 0.854806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -0.000287708 0.0223833 3.99983 0.0136689 2.92342 +EDGE_SE3:QUAT 556 987 -0.216298 -0.850254 0.00104072 -0.0122412 -0.00106367 0.326699 0.945049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000232309 0.0373913 3.99983 0.00878225 3.57338 +EDGE_SE3:QUAT 557 987 -4.79695 -0.321838 -0.192288 -0.0149424 -0.0210574 0.221293 0.974865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00248 0.00216044 -0.117844 3.99961 -0.0112389 3.80749 +EDGE_SE3:QUAT 616 987 1.45483 -6.59693 -0.0424114 -0.00950177 0.00144376 -0.510021 0.860108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 8.69493e-05 -0.0407202 3.99982 0.0155928 2.95989 +EDGE_SE3:QUAT 617 987 -2.58494 -6.54557 -0.0565828 -0.0104083 0.00168532 -0.497661 0.867308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000122816 -0.0430992 3.99979 0.0161915 3.00975 +EDGE_SE3:QUAT 988 989 4.19003 -0.352265 0.00578384 0.002923 -0.00182374 -0.0525045 0.998615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.10112e-05 -0.0126913 3.99999 0.000316727 3.98901 +EDGE_SE3:QUAT 556 988 3.59726 0.966084 -0.00259301 -0.00890864 0.0174818 0.16812 0.985571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00543 0.000726333 0.151789 3.99865 0.0130641 3.89269 +EDGE_SE3:QUAT 557 988 -0.655764 0.63184 -0.0184315 -0.00603729 -0.00338002 0.0592895 0.998217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.61885e-05 -0.0226115 3.99997 -0.000627767 3.98607 +EDGE_SE3:QUAT 558 988 -4.89683 0.786515 -0.0399204 -0.00225633 -0.00271383 0.0386503 0.999247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.91602e-05 -0.0206169 3.99997 -0.000391766 3.99413 +EDGE_SE3:QUAT 989 990 4.4499 -0.146534 -0.0187476 -0.00111174 -0.00341375 -0.00995731 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 1.2473e-05 -0.0274399 3.99995 0.000136531 3.99979 +EDGE_SE3:QUAT 557 989 3.53605 0.785308 0.0145715 -0.00292338 -0.00545708 0.00674202 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 6.81491e-05 -0.0434211 3.99988 -0.000148221 4.00029 +EDGE_SE3:QUAT 558 989 -0.701336 0.761283 -0.0125395 0.000757323 -0.00467444 -0.0137923 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -2.12893e-05 -0.0372623 3.99991 0.000257107 3.99959 +EDGE_SE3:QUAT 559 989 -4.77075 0.813355 0.0822137 0.00273719 0.0055546 -0.00737557 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 5.57692e-05 0.0446799 3.99987 -0.000163072 4.00028 +EDGE_SE3:QUAT 990 991 4.02079 -0.103057 0.0158113 0.000496533 -0.00303537 -0.00375198 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -6.85032e-06 -0.0242609 3.99996 4.56128e-05 4.00009 +EDGE_SE3:QUAT 558 990 3.76232 0.49127 0.00800093 -0.000365722 -0.00809455 -0.0240657 0.999678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00105 -2.60473e-05 -0.0648207 3.99974 0.000780135 3.99873 +EDGE_SE3:QUAT 559 990 -0.281902 0.59643 0.0103581 0.00138068 0.0019082 -0.0172211 0.999849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 9.24715e-06 0.0155443 3.99998 -0.000134525 3.99887 +EDGE_SE3:QUAT 560 990 -4.4659 0.655524 0.0275644 -0.000502453 0.00467761 -0.00910063 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -1.41519e-05 0.0373642 3.99991 -0.000170231 4.00002 +EDGE_SE3:QUAT 991 992 4.14172 -0.100698 0.0316662 0.000338782 0.0036403 -0.00251763 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 4.13505e-06 0.0291337 3.99995 -3.65754e-05 4.00019 +EDGE_SE3:QUAT 559 991 3.69135 0.359589 0.00614079 0.00181874 -0.00111036 -0.0210535 0.999776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.08705e-06 -0.0084176 4 8.70275e-05 3.99824 +EDGE_SE3:QUAT 560 991 -0.34844 0.47015 0.00348404 -4.70117e-05 0.00166804 -0.0126941 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.16008e-06 0.0133341 3.99999 -8.46158e-05 3.9994 +EDGE_SE3:QUAT 561 991 -4.53805 0.506738 -0.0708769 0.000469576 -0.00388707 -0.00268932 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -8.27233e-06 -0.0310827 3.99994 4.19655e-05 4.00021 +EDGE_SE3:QUAT 992 993 4.19676 -0.100138 0.0353196 0.00162868 -0.00368076 -0.00152501 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -2.44462e-05 -0.0294174 3.99995 2.29552e-05 4.00021 +EDGE_SE3:QUAT 560 992 3.7496 0.267146 0.0188403 0.000220859 0.00530153 -0.0151877 0.999871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 -5.56787e-06 0.042442 3.99989 -0.000322309 3.99953 +EDGE_SE3:QUAT 561 992 -0.382414 0.378619 -0.0131655 0.000814551 -0.000179512 -0.00526508 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.60755e-07 -0.00138457 4 3.60032e-06 3.99989 +EDGE_SE3:QUAT 562 992 -4.84664 0.42392 -0.0593838 -0.00126891 -0.000505675 0.00552708 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.52811e-06 -0.00396105 4 -1.08764e-05 3.99988 +EDGE_SE3:QUAT 993 994 4.26635 -0.103814 -0.0101824 0.00228657 -0.00420013 -0.00019994 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -3.85009e-05 -0.0335974 3.99993 4.32708e-06 4.00028 +EDGE_SE3:QUAT 561 993 3.63642 0.238351 0.026495 0.00227769 -0.00375912 -0.00640503 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -3.61386e-05 -0.0298972 3.99994 9.63368e-05 4.00006 +EDGE_SE3:QUAT 562 993 -0.591256 0.356795 -0.0200709 0.0003986 -0.00405676 0.00394461 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -4.91489e-06 -0.0324741 3.99993 -6.39142e-05 4.0002 +EDGE_SE3:QUAT 563 993 -4.8609 0.432567 -0.00307793 -0.00154222 0.000259075 0.0106855 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.78128e-06 0.00226997 4 1.24765e-05 3.99954 +EDGE_SE3:QUAT 994 995 4.16463 -0.0886599 -0.0274475 -0.000858873 0.0144948 -0.000463134 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00336 -5.2278e-05 0.116039 3.99916 -3.12645e-05 4.00336 +EDGE_SE3:QUAT 562 994 3.56741 0.294149 0.00619642 0.00257688 -0.00832304 0.00382393 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00109 -7.9696e-05 -0.0667167 3.99972 -0.00012343 4.00105 +EDGE_SE3:QUAT 563 994 -0.738138 0.417559 -0.0129248 0.000674021 -0.0037244 0.0105322 0.999937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -6.5579e-06 -0.0298769 3.99994 -0.000157274 3.99978 +EDGE_SE3:QUAT 564 994 -5.07518 0.51276 0.00644438 0.00272113 -0.00664157 0.0114057 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -6.07852e-05 -0.0535024 3.99982 -0.000303034 4.0002 +EDGE_SE3:QUAT 995 996 4.0503 -0.0833677 0.0456384 -0.00267682 0.00559951 -0.00142474 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -6.09695e-05 0.0447546 3.99987 -3.38928e-05 4.00049 +EDGE_SE3:QUAT 563 995 3.39171 0.424336 -0.00817403 -0.000328069 0.0106437 0.0101195 0.999892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00181 1.35488e-05 0.0852104 3.99955 0.000430811 4.0014 +EDGE_SE3:QUAT 564 995 -0.95414 0.520593 0.0354883 0.00158072 0.00785566 0.010921 0.999908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00097 6.55755e-05 0.0626401 3.99976 0.000344197 4.0005 +EDGE_SE3:QUAT 565 995 -5.41381 0.641926 -0.0128981 0.00433122 0.001114 0.00842584 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.82644e-05 0.00847292 4 3.51988e-05 3.99973 +EDGE_SE3:QUAT 996 997 4.43995 -0.0898447 0.0554421 -0.00245443 -0.00422178 -0.00165059 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 4.08299e-05 -0.0338246 3.99993 2.68813e-05 4.00028 +EDGE_SE3:QUAT 564 996 3.09011 0.512423 0.0159411 -0.0013909 0.0133341 0.00928455 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00285 -3.47655e-05 0.10688 3.99929 0.00049136 4.00251 +EDGE_SE3:QUAT 565 996 -1.37705 0.607315 0.0243749 0.00147825 0.00681635 0.0068217 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 4.77897e-05 0.0544146 3.99982 0.000187191 4.00055 +EDGE_SE3:QUAT 566 996 -5.72123 0.735194 -0.0547753 0.00269803 0.00195907 0.00192197 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.12071e-05 0.0156102 3.99998 1.52288e-05 4.00005 +EDGE_SE3:QUAT 997 998 4.34507 -0.0909379 0.0115833 -0.00168247 -0.00560126 -0.00254759 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 3.58474e-05 -0.0448658 3.99987 5.59209e-05 4.00048 +EDGE_SE3:QUAT 565 997 3.06447 0.580908 0.0190673 -0.0010748 0.00261041 0.00548338 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.03723e-05 0.0209536 3.99997 5.73393e-05 3.99999 +EDGE_SE3:QUAT 566 997 -1.29281 0.658662 -0.0202143 0.000198271 -0.00215327 0.000375535 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.66617e-06 -0.0172274 3.99998 -3.21289e-06 4.00007 +EDGE_SE3:QUAT 567 997 -5.55237 0.79492 0.0250529 0.0019384 0.00548698 -0.00574666 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 3.85592e-05 0.0440318 3.99988 -0.000125276 4.00035 +EDGE_SE3:QUAT 998 999 4.20325 -0.0953006 0.0169216 0.000420593 -0.0100128 -0.00213525 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0016 -2.20047e-05 -0.0801188 3.9996 8.66349e-05 4.00159 +EDGE_SE3:QUAT 565 998 7.42695 0.524011 0.00991283 -0.00294459 -0.00295313 0.00266708 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 3.51559e-05 -0.0235309 3.99997 -3.19527e-05 4.00011 +EDGE_SE3:QUAT 566 998 3.05177 0.563932 0.00675747 -0.00161002 -0.00788202 -0.00234528 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00099 4.73512e-05 -0.0631145 3.99975 7.16725e-05 4.00097 +EDGE_SE3:QUAT 567 998 -1.23807 0.647035 -0.013368 -0.000143595 -0.000127006 -0.00823937 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.10399e-08 -0.00103014 4 4.26317e-06 3.99973 +EDGE_SE3:QUAT 568 998 -5.3268 0.788772 0.0839078 -0.000885594 0.0113609 -0.0148487 0.999825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00205 -8.60878e-05 0.0907397 3.99949 -0.000676865 4.00118 +EDGE_SE3:QUAT 999 1000 4.16988 -0.0934421 0.0149037 0.00121085 0.00926197 -0.00411407 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00137 3.64762e-05 0.0741758 3.99966 -0.000150263 4.00131 +EDGE_SE3:QUAT 566 999 7.26107 0.452542 0.0899201 -0.00133526 -0.0176563 -0.00416996 0.999835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00499 6.35031e-05 -0.141468 3.99875 0.000285955 4.00493 +EDGE_SE3:QUAT 567 999 2.92966 0.482399 -0.000515565 0.000138281 -0.0104087 -0.0104283 0.999891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00173 -3.28785e-05 -0.08327 3.99957 0.000434981 4.0013 +EDGE_SE3:QUAT 568 999 -1.15786 0.557063 0.00297151 -0.000773316 0.00131095 -0.0170442 0.999854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.65755e-06 0.0103249 3.99999 -8.75602e-05 3.99886 +EDGE_SE3:QUAT 569 999 -5.49056 0.600302 -0.0131392 -0.00153879 -0.00283323 -0.0136739 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 1.5014e-05 -0.0229125 3.99997 0.000156924 3.99938 +EDGE_SE3:QUAT 1000 1001 4.34142 -0.149933 0.0481081 0.0032524 -0.00516459 -0.018435 0.999811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -7.7084e-05 -0.0405793 3.9999 0.00037389 3.99905 +EDGE_SE3:QUAT 567 1000 7.11423 0.28275 0.10297 0.0012398 -0.000919061 -0.0146809 0.999891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.65927e-06 -0.00713173 4 5.18342e-05 3.99915 +EDGE_SE3:QUAT 568 1000 3.01595 0.317875 0.0125389 0.000314525 0.0104409 -0.0210045 0.999725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00175 -4.18584e-05 0.0835827 3.99956 -0.000878071 3.99998 +EDGE_SE3:QUAT 569 1000 -1.31766 0.385095 0.0250826 -0.00040118 0.00654762 -0.0178658 0.999819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -2.88121e-05 0.0522777 3.99983 -0.000467281 3.99941 +EDGE_SE3:QUAT 570 1000 -5.46883 0.278785 -0.012919 -0.002804 0.00542373 0.00898202 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 -5.5002e-05 0.0436908 3.99988 0.00019472 4.00015 +EDGE_SE3:QUAT 1001 1002 4.21498 -0.248933 0.0275408 -0.0015767 0.00882281 -0.0519143 0.998611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -0.00014883 0.0693346 3.99971 -0.00179307 3.99042 +EDGE_SE3:QUAT 568 1001 7.3632 -0.0282829 -0.0358414 0.00319655 0.00529174 -0.039809 0.999188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 4.25269e-05 0.0437628 3.99988 -0.000878537 3.99414 +EDGE_SE3:QUAT 569 1001 3.00981 0.0737079 0.0141484 0.00265275 0.00144776 -0.036475 0.99933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.52467e-05 0.0127191 3.99999 -0.000238732 3.99472 +EDGE_SE3:QUAT 570 1001 -1.11714 0.188129 -0.00930189 0.000241151 0.000369322 -0.00976773 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.28279e-07 0.00298242 4 -1.46103e-05 3.99962 +EDGE_SE3:QUAT 571 1001 -5.10988 -0.233401 -0.20203 0.0019187 -0.0159011 0.0613441 0.997988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00408 0.000253219 -0.128015 3.99899 -0.00393231 3.98904 +EDGE_SE3:QUAT 1002 1003 4.1033 -0.388348 -0.0128327 -0.00505332 0.00496686 -0.0944505 0.995504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -0.000122699 0.0335112 3.99994 -0.00148662 3.9646 +EDGE_SE3:QUAT 569 1002 7.19235 -0.491328 0.0305329 0.0013128 0.0106266 -0.0883889 0.996028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00182 -0.000186116 0.0854382 3.99956 -0.00378259 3.97057 +EDGE_SE3:QUAT 570 1002 3.09304 -0.145858 0.0128983 -0.00144404 0.00923848 -0.061295 0.998076 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 -0.000173962 0.0724525 3.99968 -0.00221019 3.98628 +EDGE_SE3:QUAT 571 1002 -0.886 0.0376711 -0.0406134 0.000541117 -0.00715694 0.00955999 0.999929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -3.74858e-06 -0.0573201 3.99979 -0.000273557 4.00046 +EDGE_SE3:QUAT 572 1002 -5.10081 -0.783132 -0.0509711 0.00565643 -0.00643064 0.143279 0.989645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 4.80374e-06 -0.0594715 3.99978 -0.00444938 3.91877 +EDGE_SE3:QUAT 1003 1004 3.97954 -0.61887 0.00117517 -0.00146008 0.00243984 -0.151362 0.988474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.75515e-05 0.0162405 3.99999 -0.00114522 3.90842 +EDGE_SE3:QUAT 570 1003 7.12631 -1.02068 -0.075437 -0.00702661 0.0143298 -0.155243 0.987747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00217 -0.000929061 0.0976741 3.99954 -0.00717488 3.90597 +EDGE_SE3:QUAT 571 1003 3.2331 -0.277125 -0.000611108 -0.00395348 -0.00216215 -0.0847831 0.996389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 3.11625e-05 -0.0211141 3.99997 0.000948686 3.97136 +EDGE_SE3:QUAT 572 1003 -1.03879 0.015618 -0.00621097 0.000576995 -0.00166896 0.0491623 0.998789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -5.61005e-07 -0.0136433 3.99999 -0.000337729 3.99038 +EDGE_SE3:QUAT 573 1003 -5.29313 -0.983153 0.0303626 -0.00119885 0.00133078 0.212636 0.97713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.36794e-06 0.0128993 3.99999 0.00145323 3.81918 +EDGE_SE3:QUAT 1004 1005 4.25206 -0.977188 0.00781081 0.00585429 0.00197364 -0.209619 0.977764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 4.34409e-05 0.0290552 3.99994 -0.0035204 3.82445 +EDGE_SE3:QUAT 528 1004 1.49821 6.95176 0.0561768 0.00204043 0.0156444 -0.89164 0.452471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 -9.08767e-05 0.0218462 4.00078 0.0270864 0.819426 +EDGE_SE3:QUAT 571 1004 7.06367 -1.56201 0.0227481 -0.00473748 7.47294e-05 -0.234918 0.972004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 3.16858e-05 -0.0123146 3.99998 0.0019704 3.77929 +EDGE_SE3:QUAT 572 1004 2.97328 -0.204617 0.00283208 -0.000809767 0.000659807 -0.102295 0.994754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.32e-06 0.00420873 4 -0.000196903 3.95815 +EDGE_SE3:QUAT 573 1004 -1.39453 0.114346 0.0190063 -0.0033881 0.00316066 0.0622423 0.99805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.09951e-05 0.0276634 3.99995 0.000884798 3.98469 +EDGE_SE3:QUAT 574 1004 -5.35881 -0.876349 -0.0151434 -0.00497727 -0.000890192 0.21216 0.977222 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.44521e-05 0.00564541 3.99999 0.00106405 3.81996 +EDGE_SE3:QUAT 641 1004 3.89074 -3.91772 0.00659196 -0.0128896 -0.00488398 0.457789 0.888954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 -0.000335191 0.0334604 3.99977 0.0140177 3.16189 +EDGE_SE3:QUAT 642 1004 -0.136163 -3.79814 -0.00840351 -0.0108428 -0.00363469 0.455478 0.890174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 -0.000228966 0.0305526 3.99983 0.0121454 3.17032 +EDGE_SE3:QUAT 643 1004 -4.29526 -3.64816 -0.0334415 -0.0119101 -0.00413344 0.445172 0.895356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 -0.000277251 0.031478 3.99981 0.0124648 3.20745 +EDGE_SE3:QUAT 712 1004 0.507956 6.27608 0.0155572 0.00131981 0.0138837 -0.927711 0.373038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.00015781 0.0120263 4.00023 0.0337995 0.55706 +EDGE_SE3:QUAT 713 1004 -3.36334 6.46414 0.00259451 -0.000119577 0.0142869 -0.936918 0.349258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000278507 0.00431357 3.99986 0.0407802 0.488444 +EDGE_SE3:QUAT 1005 1006 3.97709 -0.750792 0.014677 0.00342561 0.00214424 -0.153516 0.988138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 1.52515e-05 0.022763 3.99996 -0.00189239 3.90586 +EDGE_SE3:QUAT 527 1005 2.39733 4.00228 0.0444207 0.00476508 0.0120698 -0.964525 0.263674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 8.03929e-05 0.0227104 4.00065 0.0307505 0.278508 +EDGE_SE3:QUAT 528 1005 -1.81802 4.10215 0.0148517 0.00315095 0.0114576 -0.966716 0.255577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000141391 0.0153072 4.00025 0.0325029 0.261637 +EDGE_SE3:QUAT 529 1005 -5.91788 4.35365 0.0200933 0.00169791 0.0120142 -0.971621 0.23623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000204045 0.00860444 3.99991 0.0384576 0.223639 +EDGE_SE3:QUAT 572 1005 6.93673 -2.01293 0.00199225 0.00487403 0.0020345 -0.308437 0.95123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -5.86752e-06 0.0309065 3.99994 -0.00556031 3.6197 +EDGE_SE3:QUAT 573 1005 2.94861 -0.339388 0.000520045 0.00118824 0.00488898 -0.148178 0.988948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 -6.48428e-05 0.0399162 3.99991 -0.00297725 3.91257 +EDGE_SE3:QUAT 574 1005 -1.06684 0.00871712 0.00337345 0.000165483 0.00159258 0.00288219 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.22889e-06 0.0127349 3.99999 1.83598e-05 4.00001 +EDGE_SE3:QUAT 575 1005 -5.02609 -0.832643 -0.0930735 -0.00423171 -0.00719852 0.151022 0.988495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 0.00023905 -0.0480803 3.99989 -0.00339281 3.90934 +EDGE_SE3:QUAT 641 1005 7.20411 -1.03034 0.028126 -0.00746411 -0.00291424 0.260875 0.965339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 -3.63111e-05 0.00133249 3.99999 0.00129622 3.72776 +EDGE_SE3:QUAT 642 1005 3.14413 -0.931242 0.00494802 -0.00585785 -0.00148007 0.258885 0.965889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -3.82879e-05 0.00671483 3.99999 0.00170656 3.73192 +EDGE_SE3:QUAT 643 1005 -0.893597 -0.855135 -0.0141772 -0.00689309 -0.00198946 0.247766 0.968793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -4.3623e-05 0.00518336 3.99999 0.00155019 3.75444 +EDGE_SE3:QUAT 644 1005 -4.85939 -0.740571 -0.114644 -0.00670946 -0.0101238 0.23856 0.971052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 0.000500713 -0.0556964 3.99992 -0.00560862 3.77311 +EDGE_SE3:QUAT 710 1005 4.88574 3.87252 0.0558359 0.00760902 0.0108897 -0.977312 0.211388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 -3.59119e-06 0.033226 4.00127 0.0264879 0.179223 +EDGE_SE3:QUAT 711 1005 0.754547 3.86316 0.0216502 0.00391919 0.0111699 -0.981177 0.192745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000169446 0.0171662 4.00024 0.0347708 0.148999 +EDGE_SE3:QUAT 712 1005 -3.21346 4.02323 -0.00866607 0.00234748 0.00907468 -0.985276 0.170711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000123171 0.0101533 3.99999 0.0305704 0.116839 +EDGE_SE3:QUAT 1006 1007 4.32897 -0.434873 -0.0371262 0.000548721 0.00801752 -0.0700377 0.997512 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 -9.07091e-05 0.0641429 3.99975 -0.00224674 3.98141 +EDGE_SE3:QUAT 526 1006 2.82673 2.51568 0.0133479 -0.000179605 0.0107137 -0.993243 0.115557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.3607e-05 -0.000599481 3.99958 0.0415927 0.0538526 +EDGE_SE3:QUAT 527 1006 -1.43699 2.61518 0.00707491 0.00609452 0.00957925 -0.99357 0.112652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000166765 0.0249478 4.00055 0.0316916 0.0511754 +EDGE_SE3:QUAT 528 1006 -5.65025 2.7732 -3.94007e-05 0.00443913 0.00853669 -0.994506 0.104239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000135062 0.0181217 4.00022 0.0295648 0.043768 +EDGE_SE3:QUAT 573 1006 6.45756 -2.15378 -0.0255926 0.00431439 0.00688388 -0.297957 0.954545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0009 -0.000292857 0.0624292 3.99982 -0.0096744 3.64586 +EDGE_SE3:QUAT 574 1006 2.91363 -0.720758 0.000372169 0.00323657 0.00361142 -0.150529 0.988594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -3.63768e-06 0.0336749 3.99993 -0.00265522 3.90965 +EDGE_SE3:QUAT 575 1006 -0.979387 -0.370758 -0.0211164 0.00021472 -0.00503702 -0.00224611 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -5.69441e-06 -0.0402937 3.9999 4.53925e-05 4.00039 +EDGE_SE3:QUAT 576 1006 -5.1099 -0.852967 -0.0421299 0.000973735 -0.00811943 0.0999985 0.994954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 0.000128008 -0.0651594 3.99974 -0.00326177 3.96106 +EDGE_SE3:QUAT 642 1006 6.93617 0.416801 0.0256255 -0.00247786 0.000739538 0.107491 0.994203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.61599e-06 0.00898561 3.99999 0.000538281 3.9538 +EDGE_SE3:QUAT 643 1006 2.92421 0.392634 0.0107599 -0.00370165 -1.96755e-05 0.0964101 0.995335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -9.87861e-06 0.00410074 4 0.000266508 3.96282 +EDGE_SE3:QUAT 644 1006 -1.08781 0.447714 -0.0256579 -0.00204243 -0.00801154 0.0863486 0.996231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 0.000186203 -0.0612828 3.99978 -0.00260965 3.97111 +EDGE_SE3:QUAT 645 1006 -5.08599 0.500282 -0.0321358 -0.00434631 -0.00804922 0.093878 0.995542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00078 0.000250499 -0.0586852 3.99981 -0.00267216 3.96561 +EDGE_SE3:QUAT 709 1006 5.04753 2.87995 -0.0157624 -0.00777848 0.0119754 -0.997391 0.0707585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.00036544 -0.0313203 4.00009 0.0516929 0.0209444 +EDGE_SE3:QUAT 710 1006 0.865564 2.91866 0.00506337 0.00867747 0.00885162 -0.998134 0.0597975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000219564 0.0349112 4.00111 0.0309672 0.0148495 +EDGE_SE3:QUAT 711 1006 -3.21969 3.05765 0.0036728 0.00512439 0.00838594 -0.999147 0.0401182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000164724 0.0205528 4.00022 0.0317711 0.00679644 +EDGE_SE3:QUAT 1007 1008 4.42019 -0.244377 0.0162914 -1.09384e-05 0.00149542 -0.0257709 0.999667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.44619e-06 0.0119482 3.99999 -0.000153896 3.99738 +EDGE_SE3:QUAT 524 1007 7.10673 1.75827 0.0339882 0.00357696 0.00730665 -0.998803 0.048229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000106312 0.0143651 4.00005 0.0276816 0.0095479 +EDGE_SE3:QUAT 525 1007 2.99615 1.86021 0.00578227 0.00391867 0.00719055 -0.99882 0.0478612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000110637 0.0157356 4.00011 0.0271027 0.00940893 +EDGE_SE3:QUAT 526 1007 -1.47734 1.93455 -0.020073 0.00691189 0.0108148 -0.998873 0.0456992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000279375 0.0277453 4.00046 0.0405219 0.00895794 +EDGE_SE3:QUAT 527 1007 -5.69387 2.05876 -0.0823552 0.0135014 0.0102706 -0.998955 0.0424324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99919 0.000390532 0.0541566 4.00277 0.036359 0.00826767 +EDGE_SE3:QUAT 574 1007 6.89603 -2.40118 -0.0698711 0.00485647 0.0117868 -0.219847 0.975451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0024 -0.000576011 0.099996 3.99947 -0.0112011 3.80917 +EDGE_SE3:QUAT 575 1007 3.32994 -0.816531 -0.0142258 0.00119604 0.00293134 -0.0724511 0.997367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -1.13456e-06 0.0243033 3.99996 -0.000890538 3.97915 +EDGE_SE3:QUAT 576 1007 -0.785333 -0.409758 -0.0127228 0.00137616 -3.61998e-05 0.0299986 0.999549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.48116e-07 -0.000784305 4 -1.42387e-05 3.9964 +EDGE_SE3:QUAT 577 1007 -5.20553 -0.42469 -0.0361119 -0.000117764 -0.001606 0.0572932 0.998356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.23594e-06 -0.0127041 3.99999 -0.000362568 3.98691 +EDGE_SE3:QUAT 643 1007 7.22501 0.806018 -0.0263147 -0.00380637 0.00787191 0.0260124 0.999623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00097 -8.30191e-05 0.0641123 3.99974 0.000833456 3.99832 +EDGE_SE3:QUAT 644 1007 3.23774 0.768584 0.00405409 -0.00161728 -0.000142725 0.0162919 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.86843e-07 -0.000825212 4 -5.86284e-06 3.99894 +EDGE_SE3:QUAT 645 1007 -0.727611 0.884012 -0.00271246 -0.00412748 -0.00022413 0.0237912 0.999708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.61206e-07 -0.000613554 4 -2.62104e-06 3.99774 +EDGE_SE3:QUAT 646 1007 -4.76307 0.940013 -0.0227066 -0.00485866 -0.00118515 0.0301617 0.999533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.80395e-05 -0.00771053 4 -0.000107495 3.99638 +EDGE_SE3:QUAT 708 1007 4.83071 2.65318 0.0481468 0.00464231 0.0114083 -0.999862 0.0111494 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000217276 0.0185762 3.99985 0.045208 0.00109452 +EDGE_SE3:QUAT 709 1007 0.720289 2.68984 0.0215222 -0.000620468 0.0113705 -0.999935 0.0004343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.77677e-05 -0.00248235 3.99949 0.0454812 0.000519496 +EDGE_SE3:QUAT 710 1007 -3.40685 2.82469 -0.104583 -0.0161666 -0.00948556 0.999766 0.010764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99898 0.00067417 0.0646794 4.00374 0.0393776 0.00189681 +EDGE_SE3:QUAT 1008 1009 4.02257 -0.138616 0.0197125 0.00034255 -0.0015968 -0.00999 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.78637e-06 -0.0127315 3.99999 6.35448e-05 3.99964 +EDGE_SE3:QUAT 523 1008 6.85919 1.46481 0.0401556 0.0058269 0.0081641 -0.999728 0.0210669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000183067 0.0233254 4.00032 0.0316439 0.00216176 +EDGE_SE3:QUAT 524 1008 2.67122 1.57257 0.0177129 0.00463413 0.00770038 -0.9997 0.0227699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000140638 0.0185529 4.00015 0.0299209 0.0023839 +EDGE_SE3:QUAT 525 1008 -1.45185 1.68058 -0.0139564 0.00530711 0.00744049 -0.999708 0.0223886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000151509 0.0212463 4.00027 0.0287786 0.00232504 +EDGE_SE3:QUAT 526 1008 -5.84603 1.77268 -0.0672494 0.0082841 0.0110845 -0.999704 0.0199859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000351966 0.0331612 4.00069 0.0429845 0.00233477 +EDGE_SE3:QUAT 576 1008 3.6408 -0.38905 0.00160143 0.00135027 0.00159227 0.00423283 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 8.79355e-06 0.0126693 3.99999 2.6847e-05 3.99997 +EDGE_SE3:QUAT 577 1008 -0.764908 -0.159974 -0.00748312 -0.000248594 -1.67101e-05 0.0316905 0.999498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.64943e-10 -3.9006e-05 4 -1.17677e-07 3.99598 +EDGE_SE3:QUAT 578 1008 -4.79871 -0.0569635 -0.0102568 -0.0005179 0.00129854 0.0299058 0.999552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.50729e-06 0.0105602 3.99999 0.000158743 3.99645 +EDGE_SE3:QUAT 645 1008 3.70565 0.85362 0.0168196 -0.00410905 0.00118295 -0.00139813 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.93004e-05 0.00939441 3.99999 -6.68772e-06 4.00001 +EDGE_SE3:QUAT 646 1008 -0.313226 0.96894 -0.00068292 -0.00467201 0.000265537 0.00452276 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -5.74257e-06 0.00237772 4 5.55853e-06 3.99992 +EDGE_SE3:QUAT 647 1008 -4.4765 1.04976 -0.00232599 -0.00480904 0.00215483 0.00829115 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.20157e-05 0.017715 3.99998 7.35413e-05 3.9998 +EDGE_SE3:QUAT 707 1008 4.69375 2.75103 0.0694542 -0.00636359 -0.0140635 0.999876 0.00311194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000356078 0.0254618 3.99984 0.0564178 0.000996538 +EDGE_SE3:QUAT 708 1008 0.381135 2.79594 0.0329335 -0.00568003 -0.0117208 0.999814 0.0142296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000260858 0.0227312 3.99992 0.0475104 0.00150353 +EDGE_SE3:QUAT 709 1008 -3.66108 2.92598 0.0479111 -0.000709286 -0.0110668 0.999618 0.0253173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.64131e-06 0.00283868 3.99951 0.044337 0.0030577 +EDGE_SE3:QUAT 1009 1010 4.09902 -0.149883 0.0211596 0.00229243 -0.00128303 -0.00944402 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.17246e-05 -0.0100031 3.99999 4.69112e-05 3.99967 +EDGE_SE3:QUAT 522 1009 7.07306 1.28854 0.0620869 0.00796232 0.00934774 -0.999892 0.00806525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000290995 0.0318553 4.00069 0.0368827 0.000853922 +EDGE_SE3:QUAT 523 1009 2.82747 1.41883 0.0160186 0.00390737 0.00790522 -0.999898 0.0112321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000124816 0.0156338 4.00001 0.0312616 0.000810096 +EDGE_SE3:QUAT 524 1009 -1.37803 1.51284 -0.00136982 0.00287465 0.00749112 -0.999883 0.0129927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.91588e-05 0.0115025 3.99992 0.0296537 0.000928197 +EDGE_SE3:QUAT 525 1009 -5.49649 1.6268 -0.0355698 0.0036397 0.00689575 -0.999893 0.0123961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.00010093 0.0145632 4.00004 0.027213 0.000852848 +EDGE_SE3:QUAT 577 1009 3.26979 -0.030464 0.0137727 0.000389359 -0.00174383 0.0217458 0.999762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.13608e-06 -0.0140425 3.99999 -0.000152991 3.99816 +EDGE_SE3:QUAT 578 1009 -0.76306 0.0594267 -0.00640313 -1.20202e-05 -0.000300161 0.0199578 0.999801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.74407e-08 -0.00239697 4 -2.39048e-05 3.99841 +EDGE_SE3:QUAT 579 1009 -4.79698 0.182516 -0.000286179 -0.00403006 0.00228808 0.0169963 0.999845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.67868e-05 0.0191184 3.99998 0.000164243 3.99894 +EDGE_SE3:QUAT 646 1009 3.69823 0.874524 0.0149995 -0.00455834 -0.00134705 -0.00498812 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.5163e-05 -0.0110486 3.99999 2.75762e-05 3.99993 +EDGE_SE3:QUAT 647 1009 -0.45534 0.994617 6.57825e-05 -0.0043773 0.000509025 -0.00149521 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -8.6921e-06 0.00399354 4 -2.9924e-06 4 +EDGE_SE3:QUAT 648 1009 -4.5394 1.08393 -0.00221264 -0.00518082 0.00209719 -0.000891836 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.33631e-05 0.0167216 3.99998 -7.99251e-06 4.00007 +EDGE_SE3:QUAT 706 1009 4.93138 2.92904 0.0488205 0.00526113 0.0122032 -0.999899 0.00496567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000259353 0.0210497 3.99986 0.0486046 0.000800014 +EDGE_SE3:QUAT 707 1009 0.647204 2.91167 0.0424837 -0.00453837 -0.0138215 0.999808 0.0130941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.00023666 0.0181629 3.99953 0.0557378 0.00154518 +EDGE_SE3:QUAT 708 1009 -3.61835 3.04204 0.00810785 -0.00387003 -0.0112649 0.999635 0.0242464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000156882 0.0154953 3.99968 0.0457436 0.00293506 +EDGE_SE3:QUAT 1010 1011 3.97089 -0.121422 0.0242756 -0.000296352 0.00422885 -0.00843237 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -8.62152e-06 0.0337993 3.99993 -0.000142611 4 +EDGE_SE3:QUAT 521 1010 7.09624 1.20623 0.0178839 -0.00158819 -0.00628389 0.999956 0.0067914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.81549e-05 0.00635354 3.99988 0.0252188 0.000353593 +EDGE_SE3:QUAT 522 1010 2.98413 1.36061 0.0175132 -0.00649764 -0.00711006 0.999953 0.00119008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000185605 0.025992 4.00047 0.0285079 0.000377703 +EDGE_SE3:QUAT 523 1010 -1.26175 1.46723 2.93046e-05 0.00258554 0.00578405 -0.999978 0.00177129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.00082e-05 0.0103427 3.99997 0.0230998 0.000172693 +EDGE_SE3:QUAT 524 1010 -5.45939 1.54955 -0.00258121 0.00159826 0.00483713 -0.999981 0.00355908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.13653e-05 0.00639337 3.99995 0.0193024 0.000154035 +EDGE_SE3:QUAT 577 1010 7.34939 0.0110508 0.0425333 0.00241136 -0.00281132 0.0122588 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.52992e-05 -0.0228406 3.99997 -0.000140256 3.99953 +EDGE_SE3:QUAT 578 1010 3.29631 0.0810587 0.0174692 0.00233439 -0.00155194 0.0104848 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.43171e-05 -0.0127072 3.99999 -6.69871e-05 3.9996 +EDGE_SE3:QUAT 579 1010 -0.689967 0.186775 0.00167911 -0.00159899 0.000937987 0.00737023 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.98926e-06 0.00764469 4 2.831e-05 3.9998 +EDGE_SE3:QUAT 580 1010 -5.12543 0.285682 -0.0186829 0.000252424 -0.00127417 0.00352782 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.15064e-06 -0.0102039 3.99999 -1.79953e-05 3.99998 +EDGE_SE3:QUAT 647 1010 3.63268 0.842711 0.015757 -0.00214173 -0.000865838 -0.0106398 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.60301e-06 -0.00719893 4 3.87398e-05 3.99956 +EDGE_SE3:QUAT 648 1010 -0.458609 0.940531 0.00136821 -0.00300464 0.000744823 -0.0100336 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -8.34642e-06 0.00559587 4 -2.75033e-05 3.99961 +EDGE_SE3:QUAT 649 1010 -4.67057 1.02654 -0.0393917 -0.00253624 -0.00238849 -0.0101797 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 2.33227e-05 -0.0194149 3.99998 9.89897e-05 3.99968 +EDGE_SE3:QUAT 705 1010 5.24952 3.05313 -0.0041853 -6.51523e-06 0.00598805 -0.999867 0.015151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.18607e-06 -2.58787e-05 3.99986 0.0239388 0.00106151 +EDGE_SE3:QUAT 706 1010 0.813279 3.03126 0.0268238 -0.00392267 -0.00988923 0.999935 0.00421263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000153386 0.0156933 3.99985 0.0396887 0.000526364 +EDGE_SE3:QUAT 707 1010 -3.43339 3.15421 0.0269314 -0.00300236 -0.0114332 0.999682 0.0222713 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000117769 0.0120195 3.99959 0.0462095 0.00255432 +EDGE_SE3:QUAT 1011 1012 4.34113 -0.14539 0.0284909 -0.000370907 -0.00342523 -0.00660971 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 3.22525e-06 -0.0274306 3.99995 9.05911e-05 4.00001 +EDGE_SE3:QUAT 520 1011 7.24729 1.20911 0.046077 -0.00774829 -0.00351776 0.999695 0.0231751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000139254 0.0310177 4.00088 0.0154929 0.00244902 +EDGE_SE3:QUAT 521 1011 3.12936 1.36813 0.031509 -0.00559083 -0.00682848 0.999846 0.0151472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000157909 0.0223722 4.00029 0.0279795 0.00123865 +EDGE_SE3:QUAT 522 1011 -0.972865 1.48801 -0.0100443 -0.0106208 -0.00739881 0.99987 0.00964622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000336204 0.0424905 4.00155 0.0304257 0.00105496 +EDGE_SE3:QUAT 523 1011 -5.23236 1.56477 0.00581839 -0.00673559 -0.0059153 0.999939 0.00639612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000164531 0.0269449 4.00057 0.0240089 0.000489243 +EDGE_SE3:QUAT 578 1011 7.31163 0.0484656 0.0501318 0.00181135 0.00270338 0.00194485 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.98778e-05 0.0215851 3.99997 2.12945e-05 4.0001 +EDGE_SE3:QUAT 579 1011 3.26632 0.119573 0.00926794 -0.00190291 0.0049452 -0.00104157 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 -3.82342e-05 0.0395409 3.9999 -2.17094e-05 4.00039 +EDGE_SE3:QUAT 580 1011 -1.12185 0.202988 0.0126692 -6.18341e-05 0.00295032 -0.00506508 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -1.78748e-06 0.0235986 3.99997 -5.97789e-05 4.00004 +EDGE_SE3:QUAT 581 1011 -5.13793 0.312073 0.0103538 -0.000557752 0.0045929 -0.00741559 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -1.39767e-05 0.0366932 3.99992 -0.000136298 4.00012 +EDGE_SE3:QUAT 648 1011 3.49592 0.74785 0.0141836 -0.00322262 0.00477775 -0.0181128 0.999819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -6.96971e-05 0.0375052 3.99991 -0.000339283 3.99904 +EDGE_SE3:QUAT 649 1011 -0.702911 0.827219 0.000145448 -0.00285958 0.00174033 -0.0184216 0.999825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.99339e-05 0.0132836 3.99999 -0.000120586 3.99869 +EDGE_SE3:QUAT 650 1011 -4.92179 0.932557 0.00559933 -0.00142026 0.00429245 -0.019832 0.999793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -3.26829e-05 0.0339834 3.99993 -0.000336478 3.99872 +EDGE_SE3:QUAT 704 1011 5.19534 3.08353 0.0556246 0.00564637 0.00969442 -0.999548 0.0279073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000215887 0.022616 4.00021 0.0374482 0.0035941 +EDGE_SE3:QUAT 705 1011 1.28295 3.04423 0.018783 0.00422951 0.00634056 -0.999948 0.00682804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000106473 0.0169201 4.00013 0.0251303 0.000415945 +EDGE_SE3:QUAT 706 1011 -3.12734 3.1697 0.0251929 -0.00791639 -0.0101129 0.999838 0.0125754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000328247 0.0316772 4.00055 0.0412434 0.00130869 +EDGE_SE3:QUAT 1012 1013 4.40985 -0.101467 0.021223 0.00179832 0.000480006 0.00150735 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.42202e-06 0.00380749 4 2.87125e-06 3.99999 +EDGE_SE3:QUAT 519 1012 7.09331 1.37198 0.0222552 -0.00330352 -0.0049529 0.999256 0.0381106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.6459e-05 0.0132411 4.00005 0.0207462 0.00596131 +EDGE_SE3:QUAT 520 1012 2.93742 1.54333 0.00863489 -0.00413945 -0.00412232 0.999551 0.0293846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.54128e-05 0.0165788 4.00018 0.0174273 0.00359856 +EDGE_SE3:QUAT 521 1012 -1.19056 1.64102 0.00898809 -0.00206033 -0.00706998 0.99974 0.0215805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.14141e-05 0.00824708 3.99985 0.0286024 0.00208451 +EDGE_SE3:QUAT 522 1012 -5.30652 1.69859 -0.0688758 -0.00724071 -0.00785388 0.999814 0.016088 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000238963 0.0289761 4.00055 0.0323348 0.00150665 +EDGE_SE3:QUAT 580 1012 3.1842 0.0271305 0.016201 -0.000325177 -0.000593689 -0.0111728 0.999937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 6.85632e-07 -0.00479222 4 2.6848e-05 3.99951 +EDGE_SE3:QUAT 581 1012 -0.787468 0.110858 -0.00316016 -0.00114355 0.00106346 -0.0139473 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.08206e-06 0.00831387 4 -5.7558e-05 3.99924 +EDGE_SE3:QUAT 582 1012 -5.19202 0.245402 -0.010416 -0.000380883 0.000763695 -0.0206039 0.999787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.41994e-06 0.00601153 4 -6.15993e-05 3.99831 +EDGE_SE3:QUAT 649 1012 3.62618 0.537511 0.0142882 -0.00328719 -0.00183608 -0.0247227 0.999687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.40402e-05 -0.0156499 3.99998 0.00019713 3.99762 +EDGE_SE3:QUAT 650 1012 -0.591533 0.627621 -0.00393514 -0.00197208 0.000776319 -0.0260984 0.999657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.62467e-06 0.00558684 4 -7.02143e-05 3.99728 +EDGE_SE3:QUAT 651 1012 -4.74071 0.735181 -0.0188227 -0.00213292 0.000225952 -0.0283683 0.999595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.08925e-07 0.00107973 4 -1.18729e-05 3.99678 +EDGE_SE3:QUAT 703 1012 5.00783 3.13409 0.0235799 0.00384924 0.00479206 -0.998186 0.0598831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 5.92496e-05 0.015488 4.0002 0.0171606 0.0144781 +EDGE_SE3:QUAT 704 1012 0.868432 2.97273 0.0411038 0.00208701 0.0098071 -0.999712 0.0218209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.57125e-05 0.00835611 3.99971 0.0388169 0.00229897 +EDGE_SE3:QUAT 705 1012 -3.04752 3.1217 0.0131521 0.000582292 0.00682563 -0.999976 0.000660316 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.61372e-05 0.00232933 3.99982 0.0272988 0.000189415 +EDGE_SE3:QUAT 1013 1014 4.3798 -0.0970299 0.0254655 -0.00112882 -0.00234724 -0.00270326 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 1.02681e-05 -0.0188146 3.99998 2.52986e-05 4.00006 +EDGE_SE3:QUAT 466 1013 1.60676 7.21046 0.113865 0.00869756 0.00398738 -0.478769 0.877889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -0.000343629 0.0639338 3.99986 -0.018138 3.08414 +EDGE_SE3:QUAT 518 1013 6.75819 1.60919 0.0420382 -0.00600471 -0.00416979 0.99889 0.0465425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.00013044 0.024094 4.00045 0.0188232 0.00889896 +EDGE_SE3:QUAT 519 1013 2.72613 1.78875 0.0178416 -0.00387021 -0.003044 0.999334 0.0361461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.64475e-05 0.0155102 4.00018 0.0132549 0.00533034 +EDGE_SE3:QUAT 520 1013 -1.46463 1.89806 -0.00369929 -0.00472377 -0.00223497 0.999596 0.0279263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 5.55389e-05 0.0189168 4.00032 0.00997815 0.00323395 +EDGE_SE3:QUAT 521 1013 -5.61221 1.92382 0.0187137 -0.00256551 -0.00522731 0.999783 0.0200217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.20918e-05 0.0102683 3.99998 0.0212994 0.0017433 +EDGE_SE3:QUAT 581 1013 3.59193 -0.0985609 0.00935247 0.000647798 0.00157418 -0.0120625 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.39291e-06 0.0126846 3.99999 -7.665e-05 3.99946 +EDGE_SE3:QUAT 582 1013 -0.75978 -0.0314129 -0.00184498 0.00119991 0.00113731 -0.0191647 0.999815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 5.05257e-06 0.00936941 3.99999 -9.06086e-05 3.99855 +EDGE_SE3:QUAT 583 1013 -5.1352 0.0484859 -0.0194573 0.00250571 0.00172075 -0.019074 0.999813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.6749e-05 0.0143319 3.99999 -0.000138298 3.9986 +EDGE_SE3:QUAT 650 1013 3.77941 0.311136 0.0111082 -0.000282851 0.00124206 -0.0240568 0.99971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.26671e-06 0.00984631 3.99999 -0.000118086 3.99771 +EDGE_SE3:QUAT 651 1013 -0.367 0.393054 -0.00116423 -0.000650427 0.00058607 -0.0264735 0.999649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.63634e-06 0.0044771 4 -5.8334e-05 3.9972 +EDGE_SE3:QUAT 652 1013 -4.50866 0.497512 -0.0116951 7.83106e-05 0.00226358 -0.0286724 0.999586 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -2.81948e-06 0.0181136 3.99998 -0.000259706 3.99679 +EDGE_SE3:QUAT 702 1013 4.57466 2.99354 0.0265743 0.00750932 0.00119772 -0.991649 0.128741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000141023 0.0307945 4.00091 -0.00301398 0.0665401 +EDGE_SE3:QUAT 703 1013 0.639238 2.69601 0.00738966 0.00446021 0.00300175 -0.998076 0.0617737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 2.53991e-05 0.0179482 4.00032 0.0096979 0.0153684 +EDGE_SE3:QUAT 704 1013 -3.53142 2.87523 0.0380659 0.0027564 0.00810324 -0.999687 0.023522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.65937e-05 0.0110366 3.99989 0.0318503 0.00249736 +EDGE_SE3:QUAT 771 1013 6.75785 -1.99766 0.0355135 -0.00661633 0.000416619 0.985769 0.167973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.00016106 0.0275773 4.00066 0.00709219 0.113067 +EDGE_SE3:QUAT 772 1013 0.858951 -3.75837 0.038446 -0.00718269 0.0011083 0.914493 0.404536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000394825 0.0354646 4.00058 0.0167193 0.655016 +EDGE_SE3:QUAT 773 1013 -4.97639 -2.78768 0.0495314 -0.00357673 0.003452 0.804694 0.593669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 0.000227385 0.0254074 4.00023 0.00772281 1.40998 +EDGE_SE3:QUAT 1014 1015 4.12026 -0.25174 0.0149759 -0.0042048 0.00201223 -0.0651007 0.997868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.88031e-05 0.0127197 3.99999 -0.000377573 3.98309 +EDGE_SE3:QUAT 466 1014 3.89499 3.50987 0.0728664 0.00625214 0.00264879 -0.480706 0.876855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -0.000161204 0.0448019 3.99993 -0.0128741 3.07619 +EDGE_SE3:QUAT 467 1014 -2.14658 3.82669 0.0579532 0.00385009 0.00503921 -0.272835 0.96204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -0.000130173 0.0478829 3.99988 -0.00688647 3.70282 +EDGE_SE3:QUAT 517 1014 7.01846 1.91037 -0.012008 0.000301694 -0.00820671 0.998167 0.0599648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.09909e-05 -0.00122779 3.99975 0.032387 0.0146467 +EDGE_SE3:QUAT 518 1014 2.41475 2.10119 0.0194709 -0.00369395 -0.00566194 0.998768 0.0491655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.39958e-05 0.0148246 4.00004 0.0239615 0.00986789 +EDGE_SE3:QUAT 519 1014 -1.65129 2.20716 0.0137809 -0.00147501 -0.00424765 0.999221 0.0392003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.08676e-05 0.00591171 3.99995 0.0173872 0.00623108 +EDGE_SE3:QUAT 520 1014 -5.84472 2.23646 -0.0223637 -0.00250841 -0.00370392 0.999511 0.030932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.78796e-05 0.0100473 4.00003 0.0154007 0.00391177 +EDGE_SE3:QUAT 582 1014 3.60874 -0.288765 0.0153829 9.96243e-05 -0.00115143 -0.0217181 0.999763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.14413e-06 -0.00917905 3.99999 9.95626e-05 3.99813 +EDGE_SE3:QUAT 583 1014 -0.746298 -0.213721 -0.0138224 0.00101041 -0.000525426 -0.0218086 0.999762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.07407e-06 -0.00393606 4 4.19542e-05 3.9981 +EDGE_SE3:QUAT 584 1014 -4.75484 -0.53279 -0.10599 0.00553784 -0.00728504 0.0351367 0.999341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 -0.000122221 -0.0605152 3.99977 -0.00106931 3.99598 +EDGE_SE3:QUAT 651 1014 3.98518 0.0742848 0.0150561 -0.00186252 -0.00172981 -0.0288035 0.999582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.14478e-05 -0.0144647 3.99999 0.000211188 3.99673 +EDGE_SE3:QUAT 652 1014 -0.138865 0.163665 -0.00276647 -0.00132575 4.80376e-05 -0.0310759 0.999516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.82526e-07 -0.000110323 4 4.27765e-06 3.99614 +EDGE_SE3:QUAT 653 1014 -4.13843 0.256758 -0.0228972 -0.000978074 -0.000107973 -0.0333408 0.999444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.5949e-07 -0.00125337 4 2.30602e-05 3.99555 +EDGE_SE3:QUAT 701 1014 4.01017 2.3751 0.00759731 0.0052291 0.00251692 -0.970341 0.241672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000126484 0.0229511 4.00049 -0.000891987 0.233762 +EDGE_SE3:QUAT 702 1014 0.312349 1.95697 -0.0143701 0.00508048 0.00236937 -0.992 0.126117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -3.44969e-05 0.0208386 4.00044 0.00405879 0.0637364 +EDGE_SE3:QUAT 703 1014 -3.73399 2.24738 -0.00778883 0.00206436 0.00429493 -0.998254 0.0588762 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.60764e-05 0.00830743 4.00002 0.0160624 0.0139477 +EDGE_SE3:QUAT 770 1014 6.78998 1.5915 -0.0218744 -0.000296934 0.00244514 -0.99796 0.0637924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.45574e-07 -0.00118989 3.99998 0.00983207 0.0163025 +EDGE_SE3:QUAT 771 1014 2.6361 -0.467391 0.00595228 -0.00462701 -0.00112109 0.985345 0.170504 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.28757e-05 0.0192532 4.00027 0.0102908 0.116408 +EDGE_SE3:QUAT 772 1014 -2.01687 -0.47177 0.00426051 -0.00573909 -0.00084504 0.913462 0.406882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000204774 0.02746 4.00023 0.0176558 0.662502 +EDGE_SE3:QUAT 773 1014 -6.18345 1.42131 0.0350339 -0.002586 0.00102577 0.803122 0.595808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 7.04036e-05 0.0159417 4.00006 0.00699508 1.42004 +EDGE_SE3:QUAT 1015 1016 4.11911 -0.613543 -0.0180859 -0.00120816 0.0127128 -0.1404 0.990013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00233 -0.00056644 0.0967487 3.99948 -0.00668818 3.92349 +EDGE_SE3:QUAT 466 1015 5.86669 -0.0684747 0.0431986 0.00380373 0.00710548 -0.536901 0.843607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 -0.000592808 0.0539374 4.00013 -0.0138699 2.84765 +EDGE_SE3:QUAT 467 1015 1.19321 1.47755 0.0253009 0.000439222 0.00835126 -0.33436 0.942408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -0.000457318 0.0575659 3.99993 -0.00904981 3.55363 +EDGE_SE3:QUAT 468 1015 -3.58954 0.853217 -0.0457593 -0.000286693 -0.00767414 -0.0823605 0.996573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00093 -0.000107086 -0.061064 3.99977 0.00251106 3.9738 +EDGE_SE3:QUAT 517 1015 2.94823 2.64607 0.0118822 -0.00146375 -0.0120194 0.992114 0.124752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.48019e-05 0.00580288 3.99942 0.0476517 0.0628374 +EDGE_SE3:QUAT 518 1015 -1.67262 2.76537 0.00988397 -0.00571377 -0.0097033 0.993398 0.114163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000182465 0.0231855 3.99987 0.0427067 0.0527293 +EDGE_SE3:QUAT 519 1015 -5.73492 2.77641 0.0220443 -0.00365286 -0.0083275 0.994531 0.104049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.8554e-05 0.0147731 3.9998 0.0354194 0.0436769 +EDGE_SE3:QUAT 583 1015 3.37349 -0.641327 0.00425242 -0.00320331 0.0018315 -0.0868163 0.996218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.06659e-05 0.0111661 3.99999 -0.000434185 3.96988 +EDGE_SE3:QUAT 584 1015 -0.65113 -0.500109 -0.035128 0.00149205 -0.00494843 -0.0300942 0.999534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -4.62399e-05 -0.0389982 3.99991 0.000584842 3.99676 +EDGE_SE3:QUAT 585 1015 -4.51159 -1.25707 -0.100149 -0.000841671 -0.0120664 0.120348 0.992658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00217 0.000440471 -0.0932813 3.9995 -0.00555739 3.94424 +EDGE_SE3:QUAT 652 1015 3.92818 -0.338658 0.0146205 -0.00527364 0.00233636 -0.0959849 0.995366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -3.39739e-05 0.0123956 3.99999 -0.000493951 3.96318 +EDGE_SE3:QUAT 653 1015 -0.0652331 -0.257627 -0.00393131 -0.00483363 0.00198204 -0.0980349 0.995169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -2.40305e-05 0.0099779 4 -0.000392656 3.96158 +EDGE_SE3:QUAT 654 1015 -4.139 -0.154887 -0.0514028 -0.00366617 -0.00635119 -0.100578 0.994902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -6.99052e-06 -0.0544438 3.99981 0.00279636 3.96028 +EDGE_SE3:QUAT 700 1015 4.41085 1.19929 -0.0476225 -0.00872447 0.00183792 -0.948504 0.316638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000442142 -0.0392782 4.00067 0.0254676 0.401619 +EDGE_SE3:QUAT 701 1015 0.238581 0.645663 -0.0236131 0.00604504 0.00723582 -0.983977 0.178048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 6.05089e-06 0.0256278 4.00072 0.018342 0.127063 +EDGE_SE3:QUAT 702 1015 -3.73562 1.16173 -0.037571 0.00664709 0.00689974 -0.998081 0.061181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000131095 0.0267501 4.00065 0.0241058 0.015298 +EDGE_SE3:QUAT 769 1015 6.03337 3.06271 -0.0409671 -0.00758686 0.00375328 -0.976462 0.215524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000286673 -0.0320898 4.00049 0.0257776 0.186239 +EDGE_SE3:QUAT 770 1015 2.67086 1.30715 -0.00347324 -0.00141165 -0.00662833 0.999976 0.001532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.69587e-05 0.00564699 3.99986 0.0265302 0.000193329 +EDGE_SE3:QUAT 771 1015 -1.07638 1.12817 -0.0160497 -0.0075194 -0.00492947 0.972101 0.23439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.00027714 0.0319485 4.00033 0.0303926 0.220259 +EDGE_SE3:QUAT 772 1015 -4.57456 2.74787 -0.0233038 -0.00947513 -0.00442435 0.884984 0.465505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 0.000334874 0.044519 4.00008 0.0365171 0.867702 +EDGE_SE3:QUAT 1016 1017 4.10602 -0.79767 0.021455 -0.00335565 -0.000341584 -0.184618 0.982805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.58015e-05 -0.00985936 3.99999 0.00113423 3.86369 +EDGE_SE3:QUAT 467 1016 4.00276 -1.593 -0.0562612 0.00216156 0.0209792 -0.463355 0.885922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0038 -0.00340555 0.127173 4.00057 -0.0256022 3.14503 +EDGE_SE3:QUAT 468 1016 0.355837 -0.420581 -0.002826 0.000274211 0.00499647 -0.22135 0.975182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -0.000119397 0.0377778 3.99993 -0.00409644 3.80437 +EDGE_SE3:QUAT 469 1016 -3.4222 -1.28759 -0.0422278 0.00491186 0.000906634 0.0527681 0.998594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 7.99925e-06 0.00411808 4 8.10717e-05 3.98887 +EDGE_SE3:QUAT 470 1016 -6.26707 -3.96152 -0.011225 0.00111291 0.00280874 0.32331 0.946288 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 4.1868e-05 0.0150237 4 0.00199259 3.58194 +EDGE_SE3:QUAT 516 1016 3.55416 4.14981 0.010308 -0.00725061 -0.00572247 0.963181 0.268696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000234997 0.0310856 4.00014 0.0333283 0.289334 +EDGE_SE3:QUAT 517 1016 -0.823511 4.24408 0.0114779 -0.0129161 -0.011578 0.964583 0.26321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000706993 0.0550835 4.00023 0.0638178 0.278978 +EDGE_SE3:QUAT 518 1016 -5.42843 4.27744 -0.0318515 -0.0175634 -0.00988015 0.967263 0.252976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.00154551 0.0754356 4.00196 0.0666757 0.258624 +EDGE_SE3:QUAT 584 1016 3.42925 -1.35562 -0.0139684 0.00135193 0.00806533 -0.169995 0.985411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 -0.000225303 0.0644655 3.99977 -0.00547828 3.88544 +EDGE_SE3:QUAT 585 1016 -0.356544 -0.86999 -0.0187258 -0.00186999 0.000173969 -0.0204266 0.99979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.37056e-07 0.000932633 4 -7.96253e-06 3.99833 +EDGE_SE3:QUAT 586 1016 -3.96641 -1.59554 -0.0246359 0.00180835 0.00111191 0.15251 0.9883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.87668e-06 0.0053285 4 0.000314226 3.90697 +EDGE_SE3:QUAT 653 1016 3.86398 -1.66585 -0.0297378 -0.00496113 0.0144727 -0.2371 0.971365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00202 -0.00108033 0.0925991 3.9997 -0.0100562 3.77725 +EDGE_SE3:QUAT 654 1016 -0.190328 -1.58038 -0.00802539 -0.00250425 0.00604358 -0.239522 0.970869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -0.000187453 0.0373272 3.99996 -0.00401302 3.77086 +EDGE_SE3:QUAT 655 1016 -4.20944 -1.49673 -0.0430068 -0.00132223 0.00475226 -0.239283 0.970937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.000117247 0.0311496 3.99997 -0.00344105 3.77121 +EDGE_SE3:QUAT 699 1016 5.35238 -0.17937 0.0188231 0.0037142 0.00564493 -0.951138 0.308691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -7.03362e-05 0.0181519 4.00038 0.00908638 0.38128 +EDGE_SE3:QUAT 700 1016 0.744445 -0.799511 0.00656269 0.00275327 0.00572134 -0.983566 0.180438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.08036e-05 0.0118065 4.00014 0.0172001 0.130346 +EDGE_SE3:QUAT 701 1016 -3.75358 -0.189639 -0.0878558 0.0177355 0.0113716 -0.999063 0.0378032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99863 0.000545779 0.0710936 4.00487 0.0400363 0.0073829 +EDGE_SE3:QUAT 768 1016 5.26068 3.1175 0.027168 0.00468685 0.00571888 -0.963772 0.266625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -8.0551e-05 0.0215038 4.00052 0.00962757 0.28451 +EDGE_SE3:QUAT 769 1016 2.02031 1.86722 0.0030241 0.00439161 0.0063737 -0.997062 0.0762044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 9.08754e-05 0.0177417 4.00025 0.0224663 0.0234347 +EDGE_SE3:QUAT 770 1016 -1.38352 1.95012 -0.0243808 -0.0135314 -0.00793394 0.989717 0.142175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000830866 0.0555728 4.00184 0.0452583 0.0821589 +EDGE_SE3:QUAT 771 1016 -4.34431 3.52597 -0.0746092 -0.0196837 -0.00398269 0.928956 0.369644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 0.00231626 0.0916107 4.00283 0.0610996 0.549798 +EDGE_SE3:QUAT 1017 1018 4.32575 -0.993678 -0.00168295 0.00488522 -0.00228179 -0.198825 0.98002 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -9.24455e-06 -0.00583372 4 0.000157193 3.84188 +EDGE_SE3:QUAT 468 1017 3.723 -2.90088 -0.0260134 -0.00362175 0.00544427 -0.397645 0.917516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -0.000101631 0.0181818 4.00003 -0.00171824 3.36757 +EDGE_SE3:QUAT 469 1017 0.749251 -1.64206 -0.0357672 0.00143177 0.00128783 -0.132441 0.991189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.24077e-06 0.0122817 3.99999 -0.000857403 3.92987 +EDGE_SE3:QUAT 470 1017 -2.54299 -2.07685 -0.0169703 -0.00248804 0.001751 0.142741 0.989755 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -8.17486e-06 0.0177861 3.99998 0.00136021 3.91858 +EDGE_SE3:QUAT 471 1017 -5.61612 -3.45334 -0.0374756 -0.00992013 -0.0021996 0.326598 0.945109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 -0.000154379 0.0212565 3.99993 0.00574002 3.57341 +EDGE_SE3:QUAT 516 1017 0.448372 6.94516 0.00156996 -0.00630435 -0.0100214 0.896988 0.441897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000172768 0.0245372 3.99953 0.0398452 0.781749 +EDGE_SE3:QUAT 585 1017 3.72172 -1.81892 0.00516351 -0.00505922 -0.000366059 -0.204633 0.978826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.61898e-05 -0.014823 3.99998 0.00193323 3.83255 +EDGE_SE3:QUAT 586 1017 0.17808 -1.11011 -0.0207211 -0.00167368 0.000642104 -0.0322016 0.99948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.82724e-06 0.00448253 4 -6.8672e-05 3.99586 +EDGE_SE3:QUAT 587 1017 -3.45906 -1.65169 -0.00635843 -0.00338141 0.00271828 0.144674 0.98947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.20363e-05 0.0268563 3.99995 0.00206685 3.91646 +EDGE_SE3:QUAT 654 1017 3.06864 -4.19691 -0.0318453 -0.00679349 0.00599142 -0.414826 0.909856 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 1.21158e-06 0.00616621 4.00001 0.00199013 3.31163 +EDGE_SE3:QUAT 655 1017 -0.938884 -4.10473 -0.0575075 -0.00523136 0.00500014 -0.414561 0.909993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -1.50328e-05 0.00710087 4.00001 0.00110404 3.31253 +EDGE_SE3:QUAT 656 1017 -5.30662 -4.08778 -0.071255 -0.00633442 0.00687785 -0.404116 0.91466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -8.03762e-05 0.0147319 4.00004 8.30808e-05 3.34676 +EDGE_SE3:QUAT 698 1017 5.95235 -1.3993 0.0313934 0.00541287 0.0118325 -0.975783 0.218355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000123145 0.0241281 4.00066 0.032788 0.191163 +EDGE_SE3:QUAT 699 1017 1.55453 -1.95806 0.00537049 0.00136609 0.00902757 -0.991756 0.127817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000108341 0.00574837 3.99982 0.0332699 0.0656396 +EDGE_SE3:QUAT 700 1017 -3.38231 -1.51148 0.00511629 -0.000725448 -0.00928877 0.999948 0.00409475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.4168e-05 0.00290221 3.99966 0.0371758 0.000414718 +EDGE_SE3:QUAT 767 1017 4.8708 2.7096 0.0351117 0.00485524 0.0106243 -0.962096 0.27246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 1.24181e-05 0.0231774 4.00068 0.0250274 0.29727 +EDGE_SE3:QUAT 768 1017 1.33814 1.67183 0.00110114 0.00222921 0.00952575 -0.996416 0.0840262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000124585 0.00905729 3.99982 0.0359446 0.0285878 +EDGE_SE3:QUAT 769 1017 -2.16421 2.04186 -0.0110575 -0.00286233 -0.0102299 0.993978 0.10906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.96159e-05 0.0115466 3.9996 0.0421734 0.0480594 +EDGE_SE3:QUAT 770 1017 -5.04567 3.88909 -0.0946617 -0.0122376 -0.0133575 0.946259 0.322903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 0.000367799 0.0524101 3.99945 0.0683381 0.419055 +EDGE_SE3:QUAT 1018 1019 4.02234 -0.612559 -0.01156 0.00745806 0.0188887 -0.115532 0.993096 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00605 -0.000470881 0.158556 3.99847 -0.00926678 3.95288 +EDGE_SE3:QUAT 469 1018 4.658 -3.72891 -0.0582198 0.00576058 -0.00137129 -0.32673 0.945099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 5.16314e-05 0.0117171 3.99998 -0.00324006 3.57301 +EDGE_SE3:QUAT 470 1018 1.88289 -1.79976 -0.0336428 0.00229064 -0.000381801 -0.0569225 0.998376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.16084e-06 -0.00147827 4 2.70909e-05 3.98704 +EDGE_SE3:QUAT 471 1018 -1.60651 -1.56593 -0.0302686 -0.00373359 -0.00454734 0.132145 0.991213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 9.91852e-05 -0.0295788 3.99996 -0.0018044 3.93037 +EDGE_SE3:QUAT 472 1018 -5.6966 -1.95959 -0.0849212 -0.00353969 -0.0153257 0.208609 0.977873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00275 0.00114022 -0.106141 3.99951 -0.0105162 3.82873 +EDGE_SE3:QUAT 586 1018 4.43034 -2.38778 -0.0234764 0.00290509 -0.00216611 -0.230068 0.973168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.64988e-05 -0.00823376 4 0.000585321 3.78829 +EDGE_SE3:QUAT 587 1018 0.960728 -1.3587 -0.0296667 0.00135636 0.000547129 -0.0548982 0.998491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.23051e-06 0.005249 4 -0.000152062 3.98795 +EDGE_SE3:QUAT 588 1018 -2.76782 -1.48103 -0.0857673 -0.00424051 -0.012253 0.0862464 0.996189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00207 0.000478373 -0.0926038 3.9995 -0.00393441 3.97239 +EDGE_SE3:QUAT 589 1018 -6.9414 -2.2366 -0.143811 -0.00508277 -0.017883 0.177949 0.983864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00383 0.00144331 -0.125789 3.99925 -0.0107296 3.87727 +EDGE_SE3:QUAT 697 1018 6.11162 -1.89521 -0.0800102 -0.0121799 0.0115872 -0.995195 0.0964625 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 -0.00072025 -0.0493262 4.00117 0.0546167 0.0385842 +EDGE_SE3:QUAT 698 1018 1.62201 -2.33648 -0.0131823 0.00169733 0.00742185 -0.999773 0.0199031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.74472e-05 0.00679442 3.99984 0.0293876 0.00181208 +EDGE_SE3:QUAT 699 1018 -2.86039 -2.1031 -0.00198891 0.00209297 -0.00378332 0.997417 0.0716976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.96375e-05 -0.00844745 4.00004 0.0137452 0.0206277 +EDGE_SE3:QUAT 766 1018 4.47771 1.60678 -0.0313498 -0.00779496 0.0097781 -0.983262 0.181766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000279554 -0.0322231 3.99997 0.0468841 0.132985 +EDGE_SE3:QUAT 767 1018 0.685487 1.285 -0.012732 0.0018489 0.00606343 -0.997084 0.0760449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.63319e-05 0.00748118 3.99995 0.0227858 0.023276 +EDGE_SE3:QUAT 768 1018 -3.08963 1.92821 -0.00738312 0.00134775 -0.00456237 0.993291 0.115545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.25899e-05 -0.00555432 3.99999 0.0164143 0.0534784 +EDGE_SE3:QUAT 769 1018 -6.15591 3.95605 -0.00731413 0.00211644 -0.00610118 0.952525 0.304392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -9.21215e-06 -0.0109346 4.00016 0.0142634 0.370713 +EDGE_SE3:QUAT 1019 1020 4.37842 -0.405967 0.0139332 -0.00128762 0.000936123 -0.060408 0.998173 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.01492e-06 0.0065169 4 -0.000187049 3.98541 +EDGE_SE3:QUAT 470 1019 5.81531 -2.8741 -0.0528466 0.0107536 0.0181644 -0.171681 0.984926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.006 -0.000723284 0.160878 3.99846 -0.0142096 3.88856 +EDGE_SE3:QUAT 471 1019 2.42952 -1.11466 -0.00356277 0.00176153 0.0145529 0.0168804 0.99975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00335 0.0001878 0.116102 3.99916 0.000989863 4.00223 +EDGE_SE3:QUAT 472 1019 -1.77904 -0.877547 0.0242475 0.00166064 0.00441656 0.0940544 0.995556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 6.65572e-05 0.0330031 3.99994 0.00151626 3.96489 +EDGE_SE3:QUAT 473 1019 -5.98872 -0.907693 0.0356811 0.00298275 0.00463724 0.111026 0.993802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 9.31067e-05 0.0324739 3.99994 0.00171799 3.95096 +EDGE_SE3:QUAT 587 1019 4.90555 -2.41369 -0.0528685 0.00972955 0.019005 -0.170169 0.985184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00643 -0.000877093 0.16521 3.9984 -0.0143917 3.89098 +EDGE_SE3:QUAT 588 1019 1.30901 -1.38761 -0.000436406 0.00294281 0.00643305 -0.0294328 0.999542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 4.75596e-05 0.0524436 3.99983 -0.000773882 3.99722 +EDGE_SE3:QUAT 589 1019 -2.95521 -1.40937 -0.010749 0.00107989 0.00153589 0.0631252 0.998004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 9.18264e-06 0.011398 3.99999 0.000350431 3.98409 +EDGE_SE3:QUAT 590 1019 -7.01465 -1.45329 0.0882285 0.00420958 0.00763721 0.0803477 0.996729 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 0.000215587 0.0564733 3.99982 0.00221292 3.97497 +EDGE_SE3:QUAT 696 1019 6.42084 -1.85873 0.00638678 0.00249292 0.00169847 -0.999731 0.0230083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.38959e-05 0.00997974 4.00009 0.00632647 0.00215246 +EDGE_SE3:QUAT 697 1019 2.02675 -2.06632 0.0188281 -0.0057788 -0.00450305 0.999785 0.0193933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000115898 0.0231285 4.00043 0.0188947 0.00172746 +EDGE_SE3:QUAT 698 1019 -2.44294 -1.88261 -0.0300153 -0.0197378 -0.000404452 0.995167 0.0961884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99857 0.000913049 0.0800282 4.00603 0.0166718 0.0386942 +EDGE_SE3:QUAT 699 1019 -6.77701 -0.893928 0.0098734 -0.0157296 0.0051673 0.982273 0.186723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99906 0.000855139 0.0663834 4.00416 0.00380336 0.140606 +EDGE_SE3:QUAT 765 1019 4.51703 0.691101 0.0472305 0.00702538 0.0070917 -0.996186 0.0866822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000108079 0.0284531 4.00079 0.0230068 0.0303929 +EDGE_SE3:QUAT 766 1019 0.508763 0.743356 0.0172229 0.0108675 0.00491811 -0.997699 0.0667486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 2.38877e-05 0.0437681 4.00194 0.0136847 0.0183498 +EDGE_SE3:QUAT 767 1019 -3.4009 1.28736 -0.0388115 -0.0203097 -8.30119e-05 0.999 0.0398344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99837 0.00040059 0.0814164 4.00657 0.00681204 0.00801914 +EDGE_SE3:QUAT 1020 1021 4.00778 -0.111863 0.0289076 -0.00334386 -0.00687304 -0.00715385 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 8.44425e-05 -0.0552755 3.99981 0.000194329 4.00056 +EDGE_SE3:QUAT 471 1020 6.81736 -1.36506 -0.114448 -0.000476802 0.0157546 -0.0439801 0.998908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00393 -0.000290514 0.125528 3.99903 -0.00276583 3.9962 +EDGE_SE3:QUAT 472 1020 2.59748 -0.46291 0.0012412 -8.65388e-05 0.00531713 0.0337421 0.999416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 2.10404e-05 0.0425036 3.99989 0.000717023 3.9959 +EDGE_SE3:QUAT 473 1020 -1.63201 -0.338836 0.0163376 0.00114629 0.00582694 0.0505303 0.998705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 6.61054e-05 0.0457483 3.99987 0.00114979 3.99031 +EDGE_SE3:QUAT 474 1020 -6.09947 -0.272458 -0.06525 0.00428718 0.00119182 0.0546556 0.998495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.3388e-05 0.0066854 4 0.000156779 3.98806 +EDGE_SE3:QUAT 588 1020 5.64427 -2.05815 -0.040609 0.00127297 0.00778783 -0.0896053 0.995946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00098 -9.27988e-05 0.0629289 3.99976 -0.00282849 3.96887 +EDGE_SE3:QUAT 589 1020 1.44621 -1.2568 -0.00823447 -0.000546024 0.00249458 0.00251051 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -5.07936e-06 0.0199733 3.99998 2.49984e-05 4.00007 +EDGE_SE3:QUAT 590 1020 -2.62782 -1.16444 0.0355135 0.00226111 0.00873206 0.0199254 0.999761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 0.000114192 0.0692919 3.9997 0.000693032 3.99961 +EDGE_SE3:QUAT 591 1020 -6.60547 -1.06772 -0.0771372 0.00539795 0.00127844 0.0192909 0.999799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 2.37053e-05 0.00897214 4 8.26776e-05 3.99853 +EDGE_SE3:QUAT 695 1020 6.61776 -1.5448 0.0297302 -0.00895081 -0.00348959 0.999869 0.0130532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000148562 0.0358118 4.00121 0.0148935 0.00105768 +EDGE_SE3:QUAT 696 1020 2.01403 -1.66375 0.00452271 -0.00329358 -0.00326474 0.999275 0.0378012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.86468e-05 0.0132013 4.00011 0.0140076 0.00580846 +EDGE_SE3:QUAT 697 1020 -2.32061 -1.50919 -0.0149998 -0.00688855 -0.00617579 0.996741 0.0801391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000219319 0.0277951 4.00044 0.0287011 0.0260904 +EDGE_SE3:QUAT 698 1020 -6.64436 -0.654985 -0.18608 -0.0209034 -0.00290878 0.987502 0.15619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99872 0.00171037 0.0865412 4.00603 0.0365067 0.0998296 +EDGE_SE3:QUAT 764 1020 4.27688 0.231314 0.0510651 0.0116244 0.0048467 -0.999618 0.0245904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99944 0.000148511 0.0465378 4.00213 0.0170844 0.00303358 +EDGE_SE3:QUAT 765 1020 0.153653 0.339077 0.00765399 0.00726921 0.00900803 -0.999579 0.0266175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000242641 0.0291112 4.0006 0.0344309 0.00334253 +EDGE_SE3:QUAT 766 1020 -3.88891 0.566405 -0.0601603 0.0114608 0.00715798 -0.999889 0.00631725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 0.000311179 0.0458461 4.00192 0.0280696 0.000882026 +EDGE_SE3:QUAT 1021 1022 4.20267 -0.0706393 -0.0144483 -0.00176802 -0.00387302 0.00111196 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 2.7768e-05 -0.030962 3.99994 -1.78483e-05 4.00023 +EDGE_SE3:QUAT 472 1021 6.59811 -0.312662 -0.00703443 -0.00318728 -0.00163644 0.0264718 0.999643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.01843e-05 -0.0120657 3.99999 -0.000155357 3.99723 +EDGE_SE3:QUAT 473 1021 2.34361 -0.0510242 -0.0025347 -0.00199684 -0.00143416 0.0435001 0.99905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.18732e-05 -0.0103997 3.99999 -0.000218489 3.99246 +EDGE_SE3:QUAT 474 1021 -2.09975 0.0376089 -0.0393793 0.00119324 -0.005702 0.0474173 0.998858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 1.00677e-05 -0.0461455 3.99987 -0.00109763 3.99154 +EDGE_SE3:QUAT 475 1021 -6.56088 0.218388 -0.0229851 -0.000909995 -0.000327355 0.0428103 0.999083 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.85153e-07 -0.00214473 4 -4.2523e-05 3.99267 +EDGE_SE3:QUAT 589 1021 5.4408 -1.35924 0.00757601 -0.0040715 -0.00432101 -0.00495357 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 6.87979e-05 -0.0348103 3.99992 8.45884e-05 4.0002 +EDGE_SE3:QUAT 590 1021 1.38879 -1.11662 -0.00732431 -0.000951942 0.00170104 0.0126977 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -5.67117e-06 0.0137502 3.99999 8.75338e-05 3.9994 +EDGE_SE3:QUAT 591 1021 -2.56468 -1.03163 -0.0574029 0.00201294 -0.00558769 0.01197 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -3.63264e-05 -0.0449857 3.99987 -0.000268363 3.99993 +EDGE_SE3:QUAT 592 1021 -6.92424 -0.906124 -0.00651077 0.00201462 0.00126434 0.00901518 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.02287e-05 0.00989551 3.99999 4.43509e-05 3.9997 +EDGE_SE3:QUAT 694 1021 6.84341 -1.36287 0.0609059 -0.00687741 -0.00542807 0.999866 0.0138178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000161383 0.0275182 4.00061 0.0224674 0.00107927 +EDGE_SE3:QUAT 695 1021 2.61113 -1.31984 -0.0109652 -0.00217011 -0.00679069 0.999769 0.0202555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.3386e-05 0.00868589 3.99988 0.0274864 0.00184897 +EDGE_SE3:QUAT 696 1021 -1.95183 -1.22615 0.00806005 0.0031673 -0.00680763 0.998994 0.0442137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -8.9205e-05 -0.0127117 4.00002 0.0259806 0.008029 +EDGE_SE3:QUAT 697 1021 -6.25096 -0.736381 -0.0305923 -0.000433408 -0.010026 0.996156 0.0870162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.19202e-05 0.00169993 3.99961 0.0396443 0.030684 +EDGE_SE3:QUAT 763 1021 4.5553 0.0464337 0.00253937 -0.000479684 0.00569635 -0.999913 0.0119235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.87691e-06 -0.00191914 3.99987 0.0228227 0.000699842 +EDGE_SE3:QUAT 764 1021 0.265997 0.155061 -0.0103349 0.00480269 0.0081065 -0.9998 0.0176193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000154496 0.0192216 4.00014 0.0317274 0.00158587 +EDGE_SE3:QUAT 765 1021 -3.855 0.253392 -0.0227476 0.000339293 0.0122969 -0.999734 0.0194957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.00709e-05 0.00135927 3.9994 0.0490843 0.00212343 +EDGE_SE3:QUAT 1022 1023 4.16431 -0.079918 0.00255477 0.00199409 -0.00141253 0.00344059 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.12097e-05 -0.0113824 3.99999 -1.9532e-05 3.99999 +EDGE_SE3:QUAT 473 1022 6.55303 0.22738 -0.00376457 -0.00358038 -0.00528956 0.0446109 0.998984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 9.86872e-05 -0.0402787 3.9999 -0.000885715 3.99244 +EDGE_SE3:QUAT 474 1022 2.06694 0.355606 -0.0112037 -0.000204389 -0.00989534 0.0481954 0.998789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00155 0.000120616 -0.0787957 3.99962 -0.00189805 3.99226 +EDGE_SE3:QUAT 475 1022 -2.43084 0.484253 -0.035902 -0.00253359 -0.00430426 0.0443047 0.999006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 5.96381e-05 -0.0329891 3.99993 -0.000721277 3.99242 +EDGE_SE3:QUAT 476 1022 -6.92226 0.696641 0.00885073 -0.00265653 0.00143514 0.0329919 0.999451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.52109e-05 0.0125133 3.99999 0.000211954 3.99569 +EDGE_SE3:QUAT 590 1022 5.54122 -1.10439 -0.0329727 -0.00267837 -0.00209067 0.0141096 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.29985e-05 -0.016267 3.99998 -0.000113956 3.99927 +EDGE_SE3:QUAT 591 1022 1.62553 -1.00914 -0.0269784 0.000354868 -0.00946528 0.0130496 0.99987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00143 1.46335e-05 -0.0757823 3.99964 -0.000494244 4.00075 +EDGE_SE3:QUAT 592 1022 -2.69468 -0.906836 -0.0341342 0.000178346 -0.00286652 0.0101294 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -4.70975e-08 -0.0229509 3.99997 -0.000116245 3.99972 +EDGE_SE3:QUAT 593 1022 -7.19408 -0.763898 -0.0251687 -0.00367729 0.000481077 0.00571177 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -7.65847e-06 0.00410039 4 1.19274e-05 3.99987 +EDGE_SE3:QUAT 693 1022 7.04336 -1.23705 0.0731183 -0.00925024 -0.00740036 0.999891 0.00875687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000287924 0.037007 4.00112 0.030257 0.000877948 +EDGE_SE3:QUAT 694 1022 2.60606 -1.16385 -0.0126093 -0.00294153 -0.00708401 0.999889 0.0127903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.0658e-05 0.0117697 3.99993 0.0286259 0.000893899 +EDGE_SE3:QUAT 695 1022 -1.59756 -1.06319 -0.034318 0.00181336 -0.00868925 0.999778 0.0190915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.26608e-05 -0.00725874 3.99977 0.0344479 0.00176791 +EDGE_SE3:QUAT 696 1022 -6.09709 -0.770884 0.0277885 0.00683943 -0.0087899 0.99901 0.0430715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 -0.000211704 -0.0274409 4.00056 0.0326525 0.0078763 +EDGE_SE3:QUAT 762 1022 4.59161 -0.116372 -0.0048593 -0.000104901 0.00858218 -0.999946 0.00589061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.2989e-07 -0.000419628 3.99971 0.0343294 0.0004335 +EDGE_SE3:QUAT 763 1022 0.343945 0.020537 -0.00852087 -0.00448317 0.00719513 -0.999878 0.0130837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000129589 -0.0179384 4.00009 0.0292397 0.000978952 +EDGE_SE3:QUAT 764 1022 -3.95521 0.0996764 -0.0628399 0.00104358 0.0097107 -0.999774 0.0188712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.4018e-05 0.00417779 3.99965 0.0386493 0.00180246 +EDGE_SE3:QUAT 1023 1024 4.11839 -0.076824 0.0300847 0.00182841 0.00539017 0.00355454 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 4.18131e-05 0.0430467 3.99988 7.77536e-05 4.00041 +EDGE_SE3:QUAT 474 1023 6.20131 0.669714 0.0708883 0.00163778 -0.011122 0.0516896 0.9986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.002 8.18186e-05 -0.0896733 3.9995 -0.00232138 3.99132 +EDGE_SE3:QUAT 475 1023 1.74134 0.76671 0.00284731 -0.000665026 -0.00561326 0.0474627 0.998857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 4.99839e-05 -0.044381 3.99988 -0.00104986 3.99148 +EDGE_SE3:QUAT 476 1023 -2.76211 0.878385 -0.0023055 -0.000695416 0.000246267 0.0361263 0.999347 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.57234e-07 0.00226749 4 4.27487e-05 3.99478 +EDGE_SE3:QUAT 477 1023 -7.26286 1.11068 0.0718554 -0.00327639 0.00495247 0.023423 0.999708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -5.25887e-05 0.0405108 3.9999 0.000476035 3.99822 +EDGE_SE3:QUAT 591 1023 5.76759 -0.990161 0.0539602 0.00220562 -0.0108134 0.0165576 0.999802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00187 -4.93146e-05 -0.086945 3.99953 -0.000715561 4.00079 +EDGE_SE3:QUAT 592 1023 1.48047 -0.916441 -0.00921771 0.00202012 -0.00417341 0.0137488 0.999895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -2.83322e-05 -0.033713 3.99993 -0.000231684 3.99953 +EDGE_SE3:QUAT 593 1023 -3.04648 -0.806077 -0.0240537 -0.00196097 -0.000960315 0.00937868 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.44115e-06 -0.0074608 4 -3.46814e-05 3.99966 +EDGE_SE3:QUAT 594 1023 -7.30211 -0.665041 0.0645309 -0.00297888 0.00509702 0.00525318 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 -5.78253e-05 0.0409655 3.99989 0.000105921 4.00031 +EDGE_SE3:QUAT 692 1023 7.31137 -1.13207 -0.00230645 -0.00243507 -0.00766574 0.999967 0.000602672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.44658e-05 0.00974111 3.99986 0.0306748 0.000260416 +EDGE_SE3:QUAT 693 1023 2.8796 -1.06816 -0.00183505 -0.00773918 -0.00542201 0.999944 0.00475899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000173639 0.0309583 4.00083 0.0219883 0.00045105 +EDGE_SE3:QUAT 694 1023 -1.4968 -0.967611 -0.0291828 -0.00152443 -0.00521338 0.999944 0.00911835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.02732e-05 0.00609869 3.99993 0.0209603 0.000451721 +EDGE_SE3:QUAT 695 1023 -5.75649 -0.820848 -0.0260887 0.00268676 -0.00659482 0.999851 0.0157186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.33379e-05 -0.0107519 3.99996 0.0260258 0.00118658 +EDGE_SE3:QUAT 761 1023 4.72783 -0.21865 0.0181137 0.00446619 0.0073555 -0.99996 0.00235417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000131307 0.0178662 4.00011 0.0293399 0.000317165 +EDGE_SE3:QUAT 762 1023 0.466247 -0.0834378 -0.00144231 -0.0013398 0.00650609 -0.99993 0.00978264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.19219e-05 -0.00536024 3.99986 0.0261227 0.000560604 +EDGE_SE3:QUAT 763 1023 -3.83068 -0.0010538 0.0291743 -0.005693 0.00526238 -0.999828 0.016825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000128696 -0.0227822 4.00038 0.0218041 0.00138099 +EDGE_SE3:QUAT 1024 1025 4.02806 -0.0746095 0.0384797 0.002452 -0.005771 0.00207805 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -5.50627e-05 -0.0462339 3.99987 -4.61116e-05 4.00052 +EDGE_SE3:QUAT 475 1024 5.86205 1.07194 0.0763387 0.000902906 -0.000228187 0.0512872 0.998684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.05629e-06 -0.00237302 4 -6.55393e-05 3.98948 +EDGE_SE3:QUAT 476 1024 1.30658 1.09125 0.0257555 0.000690526 0.00559475 0.0401366 0.999178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 4.49773e-05 0.0443223 3.99988 0.000887325 3.99405 +EDGE_SE3:QUAT 477 1024 -3.06687 1.22547 0.0618908 -0.00178277 0.0104753 0.0268985 0.999582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00176 -3.85062e-06 0.0843192 3.99956 0.00113278 3.99888 +EDGE_SE3:QUAT 592 1024 5.54247 -0.885185 0.059084 0.00357891 0.00115149 0.017445 0.999841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.51736e-05 0.00845853 4 7.16893e-05 3.9988 +EDGE_SE3:QUAT 593 1024 1.08513 -0.808573 0.0143015 -0.000403974 0.0044456 0.0132185 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -9.14372e-07 0.035622 3.99992 0.000235413 3.99962 +EDGE_SE3:QUAT 594 1024 -3.15096 -0.70763 0.0533629 -0.00125527 0.0105033 0.00909416 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00176 -2.87769e-05 0.0841857 3.99956 0.000380102 4.00144 +EDGE_SE3:QUAT 595 1024 -7.46638 -0.559839 0.0155353 -0.00445327 0.0065779 0.00474629 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 -0.000113021 0.0528816 3.99982 0.000121091 4.00061 +EDGE_SE3:QUAT 692 1024 3.21561 -1.04828 0.00752833 0.00761447 0.00595345 -0.999948 0.00333143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000177741 0.030459 4.00079 0.0236173 0.000415751 +EDGE_SE3:QUAT 693 1024 -1.23852 -0.947034 -0.0337555 -0.0130745 -0.00366662 0.999907 0.00112809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 0.000196716 0.0522946 4.00268 0.0147983 0.00074358 +EDGE_SE3:QUAT 694 1024 -5.61695 -0.805307 -0.0131893 -0.00708318 -0.00331119 0.999957 0.0050325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 9.94596e-05 0.0283336 4.00075 0.0135327 0.000347789 +EDGE_SE3:QUAT 760 1024 4.9293 -0.277615 0.0714335 0.0154782 0.00738657 -0.999852 0.000990383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99904 0.000453537 0.0619106 4.00362 0.0294616 0.00117908 +EDGE_SE3:QUAT 761 1024 0.630436 -0.14924 0.0125079 0.00986661 0.00561204 -0.999916 0.00632084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000208457 0.0394686 4.00145 0.0219585 0.00066979 +EDGE_SE3:QUAT 762 1024 -3.67129 -0.0758519 0.0465836 0.00395554 0.00512693 -0.999892 0.0131661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 7.87327e-05 0.0158268 4.00016 0.0200838 0.000856868 +EDGE_SE3:QUAT 1025 1026 4.01869 -0.0881613 -0.00839314 0.00112589 -0.0014972 0.0026235 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -6.62764e-06 -0.012013 3.99999 -1.5713e-05 4.00001 +EDGE_SE3:QUAT 476 1025 5.35349 1.32912 0.0191537 0.0032701 1.10505e-05 0.041839 0.999119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -3.41045e-06 -0.00155172 4 -4.39097e-05 3.993 +EDGE_SE3:QUAT 477 1025 0.901393 1.35615 0.0206917 0.000626922 0.00480366 0.0292378 0.999561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 2.79621e-05 0.0381632 3.99991 0.000557069 3.99694 +EDGE_SE3:QUAT 478 1025 -3.39169 1.49213 0.00588723 -0.00110996 -0.000226241 0.0163354 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.59432e-07 -0.00159166 4 -1.2407e-05 3.99893 +EDGE_SE3:QUAT 593 1025 5.14652 -0.784981 0.0220476 0.0020119 -0.00142404 0.0153183 0.99988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.11676e-05 -0.0117581 3.99999 -9.08897e-05 3.9991 +EDGE_SE3:QUAT 594 1025 0.860548 -0.706174 0.00886188 0.000956008 0.00482765 0.0109252 0.999928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 2.44623e-05 0.038492 3.99991 0.000210609 3.99989 +EDGE_SE3:QUAT 595 1025 -3.40094 -0.604671 0.0037751 -0.00224074 0.000869729 0.00676241 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.93846e-06 0.00713915 4 2.43011e-05 3.99983 +EDGE_SE3:QUAT 691 1025 3.58453 -1.09356 -0.0262181 -0.00257815 0.00597075 -0.99993 0.00987085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.02391e-05 -0.0103146 3.99996 0.0240811 0.000561324 +EDGE_SE3:QUAT 692 1025 -0.848177 -0.993934 -0.00980128 0.0018173 0.00344299 -0.999978 0.00544756 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.51013e-05 0.00726965 4.00001 0.0136919 0.000178784 +EDGE_SE3:QUAT 693 1025 -5.27919 -0.867373 -0.0978055 0.00747378 0.00120287 -0.999971 0.000795252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 3.49306e-05 0.0298944 4.00089 0.0047654 0.000231636 +EDGE_SE3:QUAT 759 1025 4.96848 -0.327599 0.0178655 0.00449281 0.00812868 -0.999956 0.00113785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000146152 0.0179729 4.00006 0.0324763 0.000349599 +EDGE_SE3:QUAT 760 1025 0.903602 -0.204687 -0.0119707 0.00969803 0.00504526 -0.999935 0.00308986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 0.000189588 0.0387922 4.00141 0.0199509 0.000513895 +EDGE_SE3:QUAT 761 1025 -3.38874 -0.119239 -0.0244518 0.00438562 0.00345018 -0.999949 0.00845116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 5.73744e-05 0.0175445 4.00027 0.0135031 0.00040823 +EDGE_SE3:QUAT 1026 1027 4.00759 -0.0822836 -0.0177172 -0.000341901 0.0114364 0.00283099 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00209 -6.77786e-06 0.0915434 3.99948 0.000128688 4.00206 +EDGE_SE3:QUAT 477 1026 4.95828 1.51837 -0.0267477 0.0019626 0.00339489 0.0314243 0.999498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 3.39472e-05 0.0263801 3.99996 0.000410969 3.99622 +EDGE_SE3:QUAT 478 1026 0.645769 1.54359 -0.00258381 0.000162241 -0.00171594 0.0189262 0.999819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.25359e-07 -0.0137571 3.99999 -0.00013027 3.99861 +EDGE_SE3:QUAT 479 1026 -3.76857 1.68339 -0.100586 0.00147849 -0.0141821 0.00607651 0.99988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00322 -5.48068e-05 -0.113638 3.99919 -0.000338939 4.00308 +EDGE_SE3:QUAT 594 1026 4.90693 -0.702756 -0.0375608 0.00228074 0.00312809 0.0135761 0.9999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 3.10795e-05 0.0246469 3.99996 0.000166988 3.99941 +EDGE_SE3:QUAT 595 1026 0.61399 -0.63328 -0.00901758 -0.000982311 -0.000650305 0.00936682 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.5744e-06 -0.00509135 4 -2.36812e-05 3.99966 +EDGE_SE3:QUAT 596 1026 -3.55657 -0.523941 -0.0978313 -0.000787983 -0.0138238 0.00458055 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00305 6.46771e-05 -0.110617 3.99924 -0.000257431 4.00297 +EDGE_SE3:QUAT 690 1026 3.98988 -1.17924 -0.0456466 -0.00699085 0.00615444 -0.999823 0.0163267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 -0.000185666 -0.0279755 4.0006 0.0255204 0.00142479 +EDGE_SE3:QUAT 691 1026 -0.437141 -1.09658 -0.0131526 -0.00432032 0.00469782 -0.999904 0.0123105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -8.43455e-05 -0.0172856 4.0002 0.0192113 0.00077318 +EDGE_SE3:QUAT 692 1026 -4.86837 -0.961126 -0.0356408 0.000294242 0.00204657 -0.999968 0.00778687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.65106e-06 0.00117709 3.99998 0.0081667 0.000259562 +EDGE_SE3:QUAT 758 1026 5.08765 -0.328694 -0.0616523 -0.0103826 0.00559169 -0.999914 0.0057124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99957 -0.000245792 -0.0415323 4.00158 0.0228525 0.000692302 +EDGE_SE3:QUAT 759 1026 0.911553 -0.254509 -0.0197178 0.00287833 0.00699409 -0.999965 0.00355649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.11953e-05 0.0115144 3.99994 0.0278942 0.000278264 +EDGE_SE3:QUAT 760 1026 -3.12636 -0.150123 -0.0978548 0.0081139 0.00376411 -0.999943 0.00576631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000113752 0.0324567 4.00101 0.0146861 0.00045029 +EDGE_SE3:QUAT 761 1026 -7.46152 -0.109104 -0.0692815 0.0027677 0.00205806 -0.999935 0.0108767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.11126e-05 0.0110728 4.00011 0.00798931 0.000519825 +EDGE_SE3:QUAT 1027 1028 4.07099 -0.080407 0.0327583 0.00170088 0.00215717 0.00322104 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.49599e-05 0.0171916 3.99998 2.78421e-05 4.00003 +EDGE_SE3:QUAT 478 1027 4.6522 1.60421 -0.00784258 -0.000369788 0.0097238 0.0217664 0.999716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00151 3.50564e-05 0.0778575 3.99962 0.00084749 3.99962 +EDGE_SE3:QUAT 479 1027 0.225954 1.65187 -0.00266704 0.00102008 -0.00272449 0.00901776 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -9.57221e-06 -0.0219042 3.99997 -9.875e-05 3.99979 +EDGE_SE3:QUAT 480 1027 -3.88919 1.7415 -0.0433021 0.00191339 -0.00215519 0.00377491 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.61819e-05 -0.0173281 3.99998 -3.25468e-05 4.00002 +EDGE_SE3:QUAT 595 1027 4.63739 -0.639015 -0.0201496 -0.00137937 0.0109234 0.0121834 0.999865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00191 -2.55127e-05 0.0876059 3.99952 0.000530743 4.00132 +EDGE_SE3:QUAT 596 1027 0.43724 -0.562645 -0.00287286 -0.00124782 -0.00249844 0.00765744 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.35115e-05 -0.0198715 3.99998 -7.6124e-05 3.99986 +EDGE_SE3:QUAT 597 1027 -3.72723 -0.473799 -0.0423403 -0.00175284 -0.00148145 0.00759112 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.05909e-05 -0.0116909 3.99999 -4.42615e-05 3.9998 +EDGE_SE3:QUAT 689 1027 4.45845 -1.31424 0.0257523 0.00887753 0.00401019 -0.999696 0.0226525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000101478 0.0355368 4.00123 0.0144183 0.00242042 +EDGE_SE3:QUAT 690 1027 -0.0333978 -1.22654 -0.00487467 0.00438795 0.00672469 -0.99978 0.0193545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.0001154 0.017563 4.00015 0.0261968 0.00174715 +EDGE_SE3:QUAT 691 1027 -4.44915 -1.10904 0.00440268 0.00723289 0.00526927 -0.999843 0.0152828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000136194 0.0289421 4.00075 0.0201863 0.0012456 +EDGE_SE3:QUAT 757 1027 5.33831 -0.37656 0.0151741 0.00492515 0.00673968 -0.9999 0.0114491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000130027 0.0197056 4.00022 0.0265019 0.000797014 +EDGE_SE3:QUAT 758 1027 1.06415 -0.300157 0.00481569 0.00115583 0.00595343 -0.999947 0.00832324 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.95853e-05 0.00462409 3.99988 0.0237324 0.000423272 +EDGE_SE3:QUAT 759 1027 -3.08703 -0.20392 -0.0603682 0.0145236 0.00739282 -0.999845 0.00664676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99915 0.000399646 0.0580965 4.00319 0.0288285 0.00122827 +EDGE_SE3:QUAT 760 1027 -7.12544 -0.111512 -0.17676 0.0196148 0.00418454 -0.999761 0.0086984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99845 0.000250453 0.0784544 4.00613 0.015402 0.00190132 +EDGE_SE3:QUAT 1028 1029 4.09218 -0.0729901 0.0241123 -0.00238471 -0.00534102 0.00266692 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 5.26657e-05 -0.0426553 3.99989 -5.84902e-05 4.00043 +EDGE_SE3:QUAT 479 1028 4.31062 1.64046 0.0566446 0.00246215 -0.000541108 0.0121025 0.999924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.81816e-06 -0.00468542 4 -2.90523e-05 3.99942 +EDGE_SE3:QUAT 480 1028 0.202329 1.69236 0.0131076 0.00336386 -5.04722e-05 0.00659811 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.27541e-06 -0.000670077 4 -2.50301e-06 3.99983 +EDGE_SE3:QUAT 481 1028 -3.87155 1.74963 0.0315431 0.00507846 0.00585071 0.0116309 0.999902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 0.000125797 0.0460909 3.99987 0.000270813 3.99999 +EDGE_SE3:QUAT 596 1028 4.49859 -0.592159 0.0495382 0.000319172 -9.72019e-05 0.0109153 0.99994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.30276e-07 -0.000819279 4 -4.54707e-06 3.99952 +EDGE_SE3:QUAT 597 1028 0.325362 -0.491784 0.00438168 -0.000259669 0.000767813 0.0106491 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -6.51166e-07 0.00617465 4 3.29309e-05 3.99956 +EDGE_SE3:QUAT 598 1028 -3.73079 -0.422703 0.0200223 0.00164135 0.0055886 0.0131545 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 4.61809e-05 0.0444428 3.99988 0.000293032 3.9998 +EDGE_SE3:QUAT 688 1028 4.88382 -1.50251 0.0528145 0.0127809 0.00164573 -0.999492 0.0291661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 -3.04415e-05 0.0511848 4.00263 0.00359181 0.00406151 +EDGE_SE3:QUAT 689 1028 0.400757 -1.41827 -0.00763596 0.0111729 0.00245661 -0.999598 0.0259411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 3.23803e-05 0.0447343 4.002 0.00749752 0.0032065 +EDGE_SE3:QUAT 690 1028 -4.08931 -1.30546 -0.00274409 0.00674807 0.00529901 -0.999711 0.0224589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000122475 0.0270134 4.00065 0.0199624 0.0022998 +EDGE_SE3:QUAT 756 1028 5.53658 -0.457769 0.0596234 0.0118054 0.00247062 -0.999779 0.0171911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99944 5.9674e-05 0.0472395 4.00223 0.00825809 0.00175732 +EDGE_SE3:QUAT 757 1028 1.28744 -0.381227 0.0133508 0.00691338 0.00513961 -0.999859 0.0144305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000128243 0.0276625 4.00068 0.0197548 0.00112187 +EDGE_SE3:QUAT 758 1028 -2.98503 -0.269986 0.0397004 0.00357155 0.00476342 -0.999917 0.011408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.64972e-05 0.0142894 4.00012 0.0187227 0.000659266 +EDGE_SE3:QUAT 759 1028 -7.13693 -0.172835 -0.148309 0.0168247 0.0055215 -0.999797 0.00962517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99885 0.000309389 0.0673007 4.00445 0.0208173 0.00161153 +EDGE_SE3:QUAT 1029 1030 4.12176 -0.0870888 -0.00721339 -5.54306e-06 -0.00203177 0.00185581 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 2.28914e-07 -0.0162542 3.99998 -1.50835e-05 4.00005 +EDGE_SE3:QUAT 480 1029 4.30107 1.66969 0.0344624 0.000929509 -0.00525734 0.00920828 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -1.34835e-05 -0.0421601 3.99989 -0.000193698 4.00011 +EDGE_SE3:QUAT 481 1029 0.24664 1.76706 0.0051323 0.00265408 0.00048555 0.0140597 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.42631e-06 0.00343549 4 2.31113e-05 3.99921 +EDGE_SE3:QUAT 482 1029 -4.09762 1.82024 0.0532011 0.00434262 0.00362498 0.0227708 0.999725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 6.62008e-05 0.0277914 3.99995 0.000313148 3.99812 +EDGE_SE3:QUAT 597 1029 4.43159 -0.490566 0.0258553 -0.00267525 -0.00482647 0.0129643 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 5.80296e-05 -0.0381885 3.99991 -0.000248153 3.99969 +EDGE_SE3:QUAT 598 1029 0.362131 -0.387068 -0.000421067 -0.000859793 0.000292043 0.0156906 0.999876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.06102e-06 0.00249734 4 2.00116e-05 3.99902 +EDGE_SE3:QUAT 599 1029 -4.1156 -0.289962 0.00783334 -0.000169917 0.000945904 0.0157604 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.05708e-07 0.00759657 4 5.99365e-05 3.99902 +EDGE_SE3:QUAT 687 1029 4.79302 -1.76218 -0.00426519 0.00069006 0.00380887 -0.999479 0.0320487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.36774e-05 0.00276556 3.99995 0.0150196 0.00416684 +EDGE_SE3:QUAT 688 1029 0.781655 -1.6583 -0.0274323 0.00740716 0.00408882 -0.999461 0.0317339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 8.1796e-05 0.0296739 4.00086 0.0144398 0.0043007 +EDGE_SE3:QUAT 689 1029 -3.70182 -1.54385 -0.0843981 0.00591108 0.00470087 -0.999561 0.028659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 9.07911e-05 0.0236744 4.00051 0.017414 0.00350145 +EDGE_SE3:QUAT 755 1029 5.73976 -0.595141 0.0417081 0.00500353 0.00484338 -0.999689 0.0239576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 8.61822e-05 0.0200322 4.00033 0.0183897 0.00248084 +EDGE_SE3:QUAT 756 1029 1.44643 -0.516597 -0.00694444 0.00643608 0.00472 -0.999768 0.0199943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000104496 0.0257602 4.0006 0.017836 0.00184461 +EDGE_SE3:QUAT 757 1029 -2.80633 -0.429458 -0.0218101 0.00170335 0.00736514 -0.999822 0.0172834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.62264e-05 0.00681733 3.99984 0.0292029 0.00141976 +EDGE_SE3:QUAT 758 1029 -7.06261 -0.290846 0.0318996 -0.00153772 0.0071229 -0.999866 0.0146502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.8549e-05 -0.00615312 3.99983 0.0286561 0.00107332 +EDGE_SE3:QUAT 1030 1031 4.0353 -0.0907717 0.00771839 -0.00176877 0.00183035 -0.00682024 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.33185e-05 0.0144971 3.99999 -4.94129e-05 3.99987 +EDGE_SE3:QUAT 481 1030 4.36396 1.8022 -0.00359436 0.00255607 -0.00168178 0.0160839 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.68727e-05 -0.0139423 3.99999 -0.000113251 3.99901 +EDGE_SE3:QUAT 482 1030 0.031576 1.92907 0.0158371 0.00445724 0.00146741 0.0246699 0.999685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.32707e-05 0.0104093 3.99999 0.000123122 3.99759 +EDGE_SE3:QUAT 483 1030 -4.27647 2.00728 -0.0348523 0.00260918 -0.00320603 0.0277032 0.999608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -2.77336e-05 -0.0264865 3.99996 -0.000370111 3.99711 +EDGE_SE3:QUAT 598 1030 4.45738 -0.337351 -0.0127831 -0.000772835 -0.00166215 0.0182082 0.999833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.23094e-06 -0.0131219 3.99999 -0.000118984 3.99872 +EDGE_SE3:QUAT 599 1030 0.00833631 -0.231541 -0.0105925 -7.09347e-05 -0.00108941 0.0179791 0.999838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 8.18597e-07 -0.00869576 4 -7.81155e-05 3.99873 +EDGE_SE3:QUAT 600 1030 -4.2711 -0.151339 -0.00970349 0.00123357 3.59822e-05 0.0182822 0.999832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.50607e-08 1.71449e-05 4 -6.68338e-07 3.99866 +EDGE_SE3:QUAT 686 1030 4.6376 -2.05424 -0.0269398 -0.00272045 0.00279053 -0.999516 0.0308486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.34628e-05 -0.0108968 4.00008 0.0118067 0.00387114 +EDGE_SE3:QUAT 687 1030 0.669983 -1.94013 -0.0131868 -0.00146246 0.00403033 -0.999416 0.0339141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.0496e-05 -0.00585879 3.99996 0.0164713 0.00467716 +EDGE_SE3:QUAT 688 1030 -3.30115 -1.84094 -0.0976536 0.0055444 0.00420921 -0.999384 0.0343865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 7.11573e-05 0.0222183 4.00046 0.0152662 0.00491164 +EDGE_SE3:QUAT 754 1030 5.90066 -0.740171 -0.00950041 -0.000267284 0.00434752 -0.999369 0.0352432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.83275e-07 -0.00106961 3.99992 0.0174112 0.0050445 +EDGE_SE3:QUAT 755 1030 1.61321 -0.704378 -0.00867309 0.00288808 0.0046459 -0.999642 0.0262017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.23585e-05 0.0115652 4.00006 0.0179474 0.00286016 +EDGE_SE3:QUAT 756 1030 -2.66224 -0.598618 -0.0735142 0.00447009 0.00461097 -0.999736 0.0220647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 7.49977e-05 0.0178941 4.00026 0.0176346 0.00210527 +EDGE_SE3:QUAT 757 1030 -6.9161 -0.492316 -0.0457734 0.000251758 0.00755831 -0.999777 0.0197075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.65242e-05 0.00100823 3.99978 0.0301634 0.00178136 +EDGE_SE3:QUAT 1031 1032 4.36666 -0.221949 0.0490212 0.000133251 -0.000955188 -0.0403433 0.999185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.37098e-06 -0.00755844 4 0.000151911 3.9935 +EDGE_SE3:QUAT 482 1031 4.0612 2.02384 0.0104737 0.00254569 0.0032417 0.0174332 0.99984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 3.63451e-05 0.02539 3.99996 0.000220376 3.99895 +EDGE_SE3:QUAT 483 1031 -0.250324 2.13748 0.000211543 0.000946167 -0.00143861 0.0206746 0.999785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -4.52925e-06 -0.0117362 3.99999 -0.000122059 3.99832 +EDGE_SE3:QUAT 484 1031 -4.47968 2.22869 -0.0440992 -0.00312022 0.000307795 0.0193472 0.999808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.27886e-06 0.00318516 4 3.31327e-05 3.99851 +EDGE_SE3:QUAT 599 1031 4.04553 -0.179448 0.0129519 -0.0020648 0.000807349 0.0111283 0.999936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.86015e-06 0.00673328 4 3.79399e-05 3.99952 +EDGE_SE3:QUAT 600 1031 -0.208751 -0.100792 0.00716096 -0.000674603 0.00175527 0.0113163 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -3.93153e-06 0.0141312 3.99999 8.00762e-05 3.99954 +EDGE_SE3:QUAT 601 1031 -4.27438 -0.0981671 -0.0372629 -0.000210513 0.000866057 0.0226596 0.999743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.23781e-07 0.00698036 4 7.92788e-05 3.99796 +EDGE_SE3:QUAT 685 1031 5.00991 -2.45015 0.00290484 0.0082811 0.00887661 -0.999909 0.00593943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000288076 0.0331287 4.0008 0.0351219 0.000723809 +EDGE_SE3:QUAT 686 1031 0.603833 -2.20107 0.0111793 -0.00168948 0.004724 -0.999704 0.0238213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.90226e-05 -0.00676339 3.99995 0.019191 0.00237338 +EDGE_SE3:QUAT 687 1031 -3.33501 -2.11032 0.00824056 0.000301361 0.00562569 -0.99962 0.0269652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.34483e-05 0.00120773 3.99988 0.0223966 0.00303434 +EDGE_SE3:QUAT 753 1031 5.9417 -0.93469 0.00816375 0.00589312 0.0078932 -0.999156 0.0398813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.00016801 0.0236339 4.0004 0.0295756 0.00672097 +EDGE_SE3:QUAT 754 1031 1.84969 -0.92409 0.00945253 0.00085761 0.00618084 -0.999582 0.0282434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.90343e-05 0.00343589 3.99987 0.0244801 0.00334365 +EDGE_SE3:QUAT 755 1031 -2.38236 -0.821118 -0.016022 0.00464613 0.00660826 -0.99978 0.0193356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.00011884 0.0185962 4.0002 0.0256926 0.00174703 +EDGE_SE3:QUAT 756 1031 -6.67241 -0.685929 -0.101262 0.00636232 0.00655292 -0.999839 0.0154168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000156537 0.0254594 4.00051 0.0254169 0.00127431 +EDGE_SE3:QUAT 1032 1033 4.18392 -0.361173 0.0344572 -0.000719613 0.00494321 -0.0737902 0.997261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -5.55497e-05 0.0385913 3.99991 -0.00141277 3.97859 +EDGE_SE3:QUAT 483 1032 4.12504 2.10425 0.062527 0.000922963 -0.002293 -0.0192278 0.999812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.07099e-05 -0.0181212 3.99998 0.000173624 3.9986 +EDGE_SE3:QUAT 484 1032 -0.116122 2.22196 0.000984996 -0.00320375 -0.000681717 -0.0202218 0.99979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.0111e-05 -0.00622753 4 6.55308e-05 3.99837 +EDGE_SE3:QUAT 485 1032 -4.23895 2.34016 -0.0606093 -0.00282644 -0.00429588 -0.0269582 0.999623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 3.78086e-05 -0.0352455 3.99992 0.000477808 3.9974 +EDGE_SE3:QUAT 600 1032 4.16072 -0.221534 0.0419306 -0.000438157 0.000642003 -0.0291347 0.999575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.35311e-06 0.00497639 4 -7.17217e-05 3.99661 +EDGE_SE3:QUAT 601 1032 0.0953066 -0.117316 0.00177077 -0.000374002 0.000116277 -0.0173853 0.999849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.5932e-07 0.000851782 4 -7.17706e-06 3.99879 +EDGE_SE3:QUAT 602 1032 -4.20011 -0.311112 -0.0790851 -0.00139185 -0.00539846 0.0376767 0.999274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 5.50925e-05 -0.042471 3.99989 -0.000796744 3.99477 +EDGE_SE3:QUAT 684 1032 4.55534 -2.79167 -0.00789492 -0.00882998 -0.0132999 0.994832 0.100269 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000443697 0.0357523 4 0.0588892 0.0414126 +EDGE_SE3:QUAT 685 1032 0.651236 -2.2919 -0.0123274 -0.00702155 -0.00893365 0.999369 0.0336612 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.00026484 0.0281345 4.00037 0.0375297 0.00508285 +EDGE_SE3:QUAT 686 1032 -3.75882 -2.2115 0.0756447 0.00292628 -0.00429849 0.999855 0.0162231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.91699e-05 -0.0117101 4.00007 0.0168037 0.00115766 +EDGE_SE3:QUAT 752 1032 6.01188 -0.900006 0.00457527 0.00387061 0.00713281 -0.999483 0.031104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000110183 0.0155075 4.00008 0.027502 0.00411928 +EDGE_SE3:QUAT 753 1032 1.5734 -1.06295 0.00575539 -0.00478937 -0.00809693 0.999956 0.000157546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.00015515 0.0191592 4.0001 0.0323968 0.000354239 +EDGE_SE3:QUAT 754 1032 -2.49965 -0.961175 0.0528086 0.000115088 -0.00635054 0.999914 0.011457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.60767e-06 -0.000460572 3.99984 0.0253828 0.000686207 +EDGE_SE3:QUAT 755 1032 -6.71507 -0.769277 -0.00736967 -0.00368639 -0.00631405 0.999755 0.0208765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.26212e-05 0.0147556 4.00003 0.0258453 0.00196484 +EDGE_SE3:QUAT 1033 1034 4.23972 -0.487065 -0.0191829 -0.00417289 0.00484901 -0.112967 0.993578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -0.000112063 0.0324438 3.99995 -0.00171408 3.94922 +EDGE_SE3:QUAT 484 1033 4.036 1.67583 0.0367833 -0.00362197 0.00409352 -0.0939723 0.99556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -7.872e-05 0.0282554 3.99996 -0.00125816 3.96488 +EDGE_SE3:QUAT 485 1033 -0.0921915 1.76191 0.00676126 -0.00288568 0.00029257 -0.100092 0.994974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.32549e-06 -0.00113738 4 0.000115329 3.95993 +EDGE_SE3:QUAT 486 1033 -4.18663 1.98523 0.0122276 -0.00136783 -0.00132384 -0.12588 0.992044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.04516e-06 -0.0123844 3.99999 0.000817419 3.93665 +EDGE_SE3:QUAT 601 1033 4.25122 -0.6209 0.0298928 -0.00103593 0.00502616 -0.0909113 0.995846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -7.16423e-05 0.0385909 3.99991 -0.00173049 3.96731 +EDGE_SE3:QUAT 602 1033 -0.0160545 -0.35919 -0.00139194 -0.00190234 -0.000582932 -0.03543 0.99937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.07843e-06 -0.00546278 4 0.000101478 3.99499 +EDGE_SE3:QUAT 603 1033 -4.1312 -0.906384 -0.0316048 0.00457696 -0.00478524 0.0893167 0.995981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -4.26059e-05 -0.0427076 3.99988 -0.00197093 3.96855 +EDGE_SE3:QUAT 683 1033 4.15151 -2.21064 -0.0544737 0.0052429 -0.0145974 0.961466 0.274487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 -0.000123025 -0.0256167 4.00084 0.0370536 0.301952 +EDGE_SE3:QUAT 684 1033 0.539255 -1.59131 -0.0240427 -0.0128857 -0.0142077 0.984666 0.173392 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000801499 0.0532477 4.00036 0.0699668 0.122236 +EDGE_SE3:QUAT 685 1033 -3.45173 -1.65971 -0.0295241 -0.0114209 -0.0103784 0.994194 0.106493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000628932 0.0463656 4.00103 0.0499856 0.0465356 +EDGE_SE3:QUAT 751 1033 6.43693 0.155083 0.00852455 -0.00158019 0.00230705 -0.997543 0.0699954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.46872e-05 -0.00636078 4.00001 0.00999594 0.0196326 +EDGE_SE3:QUAT 752 1033 1.82192 -0.79909 0.0116372 -0.00814033 -0.00843359 0.999025 0.0425623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000310289 0.0326481 4.00063 0.036359 0.00784409 +EDGE_SE3:QUAT 753 1033 -2.57621 -0.699441 0.00757956 -0.009172 -0.00920326 0.997223 0.0733258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.00040711 0.0369597 4.00071 0.0416847 0.0222861 +EDGE_SE3:QUAT 754 1033 -6.63711 -0.518365 0.0938029 -0.00446636 -0.00717935 0.996403 0.0843241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000119964 0.0180221 3.99999 0.0312012 0.0287688 +EDGE_SE3:QUAT 1034 1035 4.02718 -0.578527 0.0112718 9.86736e-05 7.65791e-05 -0.132142 0.991231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.34114e-08 0.000751303 4 -5.27266e-05 3.93015 +EDGE_SE3:QUAT 485 1034 3.96162 0.43538 -0.0126688 -0.0064084 0.00517786 -0.211951 0.977246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00011108 0.0228498 3.99999 -0.00174642 3.82043 +EDGE_SE3:QUAT 486 1034 -0.202251 0.45614 0.00319067 -0.00436537 0.00367395 -0.236979 0.971498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.15278e-05 0.0150007 4 -0.0011866 3.77541 +EDGE_SE3:QUAT 487 1034 -4.14493 1.11849 -0.000559877 -0.00779155 0.00599198 -0.335974 0.94182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -3.48463e-05 0.0109992 4.00002 0.000392258 3.54847 +EDGE_SE3:QUAT 602 1034 4.16933 -1.14005 -0.0180485 -0.00582828 0.00416323 -0.148241 0.988925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.65413e-05 0.0219968 3.99998 -0.00134821 3.91222 +EDGE_SE3:QUAT 603 1034 0.131277 -0.638757 -0.0121032 0.000480347 0.000180306 -0.0235241 0.999723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.68351e-07 0.0015768 4 -1.90729e-05 3.99779 +EDGE_SE3:QUAT 604 1034 -3.90013 -1.23078 -0.0212627 -8.3833e-05 -9.196e-05 0.140328 0.990105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.1576e-08 -0.000574741 4 -3.65094e-05 3.92123 +EDGE_SE3:QUAT 682 1034 5.04565 -0.541976 0.007549 -0.00214694 -0.0134963 0.856995 0.515143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 -0.00017455 -0.00349356 4.00004 0.0282125 1.06189 +EDGE_SE3:QUAT 683 1034 0.816376 0.449067 0.019034 0.000826563 -0.0164388 0.924216 0.381515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -0.00026029 -0.0112483 4.00019 0.0409378 0.582824 +EDGE_SE3:QUAT 684 1034 -3.28579 0.30347 -0.114364 -0.0166191 -0.0186787 0.958677 0.283396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 0.000866838 0.0706421 3.99922 0.0948035 0.324947 +EDGE_SE3:QUAT 750 1034 6.29364 1.48228 0.0178667 0.00387965 0.00613256 -0.99072 0.135723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 5.77566e-05 0.0160641 4.00025 0.019275 0.0738447 +EDGE_SE3:QUAT 751 1034 2.17266 0.0180726 0.00769609 -0.00273651 -0.00631341 0.999056 0.0428813 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.11967e-05 0.0109728 3.99993 0.0260749 0.00755566 +EDGE_SE3:QUAT 752 1034 -2.35821 0.0749324 -0.0680467 -0.0123031 -0.0130088 0.9877 0.155335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000751179 0.0505922 4.00056 0.0638684 0.098206 +EDGE_SE3:QUAT 753 1034 -6.70376 0.40949 -0.0739409 -0.0131339 -0.014079 0.982434 0.185616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000817236 0.0544867 4.00035 0.0703807 0.139844 +EDGE_SE3:QUAT 1035 1036 4.04928 -0.614707 0.0140288 0.0051099 0.00315131 -0.13016 0.991475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 4.23268e-05 0.0324647 3.99993 -0.0022703 3.9325 +EDGE_SE3:QUAT 486 1035 3.10486 -1.90768 0.000675964 -0.00462568 0.00317586 -0.363515 0.931571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.86039e-06 0.00213992 4 0.00115816 3.47141 +EDGE_SE3:QUAT 487 1035 -1.39005 -1.85324 0.0044126 -0.00852437 0.00499916 -0.457102 0.889359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000143247 -0.0121087 3.99994 0.0073534 3.1642 +EDGE_SE3:QUAT 488 1035 -6.11645 -0.0478365 -0.0289951 -0.00874638 0.00466437 -0.635116 0.772353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000162597 -0.0315389 3.99979 0.0195108 2.3867 +EDGE_SE3:QUAT 603 1035 4.11672 -1.4004 -0.00390986 0.000557754 0.000410502 -0.155652 0.987812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.13252e-07 0.00419036 4 -0.000349981 3.90309 +EDGE_SE3:QUAT 604 1035 0.121869 -0.649925 -0.00732816 -5.92549e-05 -2.73771e-05 0.00840905 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.39676e-09 -0.000213015 4 -8.87212e-07 3.99972 +EDGE_SE3:QUAT 605 1035 -3.91204 -1.25053 -0.0448882 -0.00432968 -0.00349838 0.177926 0.984028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.71948e-05 -0.0176187 3.99999 -0.00125381 3.87344 +EDGE_SE3:QUAT 682 1035 3.66116 3.26657 0.0738444 -0.000446961 -0.0136146 0.781558 0.623684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.00033475 -0.0239352 4.0006 0.0108098 1.55639 +EDGE_SE3:QUAT 683 1035 -1.62197 3.69782 0.104832 0.00273182 -0.016052 0.865777 0.500166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000403002 -0.0302548 4.00117 0.0195854 1.00125 +EDGE_SE3:QUAT 684 1035 -6.33772 2.96644 -0.157179 -0.0141671 -0.0204192 0.912995 0.407213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000427518 0.0578944 3.99795 0.0883119 0.666489 +EDGE_SE3:QUAT 749 1035 5.81075 2.41495 0.0197231 0.00375709 0.0085857 -0.980083 0.198369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 8.52422e-05 0.016425 4.00028 0.0252868 0.157642 +EDGE_SE3:QUAT 750 1035 2.28625 0.921637 0.000602248 0.00308074 0.00643876 -0.999967 0.00378118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.97234e-05 0.0123239 3.99999 0.0256618 0.000259791 +EDGE_SE3:QUAT 751 1035 -1.78544 0.950216 0.0043135 -0.00206805 -0.006704 0.984659 0.17435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.01403e-06 0.00835662 3.99982 0.0275961 0.121806 +EDGE_SE3:QUAT 752 1035 -6.00305 1.82128 -0.112692 -0.0104518 -0.0146362 0.95861 0.284154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 0.00020612 0.0438829 3.99921 0.0689021 0.324746 +EDGE_SE3:QUAT 1036 1037 4.08742 -0.570174 -0.0160882 0.00101797 0.0103748 -0.11364 0.993467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00171 -0.000252215 0.0828034 3.9996 -0.00470318 3.95006 +EDGE_SE3:QUAT 487 1036 0.474812 -5.50591 0.0274686 -0.00309446 0.0042676 -0.569171 0.822203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 5.47865e-06 0.00240584 4.00001 0.00317342 2.70415 +EDGE_SE3:QUAT 488 1036 -5.93083 -4.11576 0.0130421 -0.00322611 0.00270817 -0.730236 0.683182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.17815e-05 -0.0113114 3.99996 0.00992846 1.86704 +EDGE_SE3:QUAT 604 1036 4.16915 -1.18054 0.00491665 0.00486748 0.00310678 -0.121711 0.992549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 4.04835e-05 0.0313438 3.99993 -0.00203891 3.94099 +EDGE_SE3:QUAT 605 1036 0.0769548 -0.392331 -0.00213615 0.000886959 -1.62265e-05 0.0483912 0.998828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.56459e-07 -0.000643604 4 -1.97226e-05 3.99063 +EDGE_SE3:QUAT 606 1036 -4.13508 -0.871007 -0.0595081 -0.00177573 -0.0104581 0.195354 0.980675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00138 0.000504151 -0.0748851 3.99974 -0.00703035 3.84874 +EDGE_SE3:QUAT 748 1036 5.4882 2.59105 -0.0379634 -0.00871552 0.00819439 -0.966619 0.255938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000319449 -0.0370245 4.00008 0.0442159 0.262886 +EDGE_SE3:QUAT 749 1036 1.86168 1.38658 0.000120948 0.00662334 0.00442951 -0.997576 0.0691263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 4.69614e-05 0.0266937 4.00071 0.0138648 0.0193412 +EDGE_SE3:QUAT 750 1036 -1.75766 1.50102 0.000398547 -0.00556155 -0.00157199 0.991954 0.126468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000115008 0.0227484 4.00041 0.0115767 0.0641412 +EDGE_SE3:QUAT 751 1036 -5.36674 2.88485 0.0276516 -0.00314845 -0.0010741 0.953644 0.300917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.40451e-05 0.0139513 4.00008 0.0102487 0.362284 +EDGE_SE3:QUAT 1037 1038 4.20394 -0.449337 0.0188531 1.68944e-05 0.000212939 -0.0820237 0.99663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.51296e-08 0.0017029 4 -6.98303e-05 3.97309 +EDGE_SE3:QUAT 605 1037 4.19135 -0.56411 -0.0238365 0.00122398 0.0106606 -0.0654151 0.9978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00183 -0.000127638 0.0857306 3.99955 -0.00280853 3.98472 +EDGE_SE3:QUAT 606 1037 -0.172609 0.168948 0.0075294 -0.00172448 -0.000103198 0.0827756 0.996567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.25351e-06 0.000888006 4 6.05013e-05 3.97259 +EDGE_SE3:QUAT 607 1037 -4.23923 -0.0209666 -0.00373327 -0.00426885 0.000155294 0.156863 0.987611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.19088e-05 0.00910038 3.99999 0.000922465 3.9016 +EDGE_SE3:QUAT 747 1037 5.62901 1.44075 0.0365564 0.00481611 0.00557825 -0.974961 0.222254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -4.26403e-05 0.0211272 4.0005 0.0114671 0.197743 +EDGE_SE3:QUAT 748 1037 1.66482 1.05978 0.00652937 0.000750122 0.00903037 -0.989452 0.144575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000101868 0.00331226 3.99978 0.033398 0.0838962 +EDGE_SE3:QUAT 749 1037 -2.24113 1.38253 -0.0664686 -0.0168106 -0.00490754 0.998838 0.0449055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99895 0.000615819 0.0674394 4.00423 0.0255985 0.00936933 +EDGE_SE3:QUAT 750 1037 -5.53554 3.04007 -0.0528057 -0.0155575 2.36562e-07 0.971057 0.238339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99945 0.001244 0.067313 4.00324 0.0280202 0.228606 +EDGE_SE3:QUAT 1038 1039 4.16226 -0.311105 0.0299391 0.000341609 0.000778464 -0.0637724 0.997964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.32631e-07 0.00645049 4 -0.000208051 3.98374 +EDGE_SE3:QUAT 606 1038 4.06809 0.41249 0.0268508 -0.0017753 5.48636e-06 0.000417199 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.94779e-08 5.27784e-05 4 1.1626e-08 4 +EDGE_SE3:QUAT 607 1038 -0.111822 0.857988 0.00931017 -0.00396328 0.000117106 0.0751048 0.997168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.0864e-05 0.00448738 4 0.000213103 3.97744 +EDGE_SE3:QUAT 608 1038 -4.32236 0.883413 0.00271856 -0.00465193 0.00100218 0.0926364 0.995689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -2.93324e-05 0.0130559 3.99999 0.000682722 3.96572 +EDGE_SE3:QUAT 746 1038 5.62047 -0.0049715 0.0266938 0.00415064 0.00946807 -0.987444 0.157631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000134632 0.0175069 4.00025 0.0304404 0.0997093 +EDGE_SE3:QUAT 747 1038 1.61501 0.0177562 0.0104873 0.00464757 0.00598639 -0.989935 0.141321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 4.27882e-05 0.0192737 4.00039 0.0176114 0.0800618 +EDGE_SE3:QUAT 748 1038 -2.49482 0.291094 0.0194539 0.000381155 0.0091959 -0.997984 0.0628011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.46515e-05 0.00155239 3.99969 0.0362294 0.016106 +EDGE_SE3:QUAT 749 1038 -6.36005 2.19689 -0.180015 -0.0168278 -0.00625907 0.991756 0.126875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9992 0.00111662 0.0688272 4.00356 0.0408984 0.0660119 +EDGE_SE3:QUAT 1039 1040 4.24478 -0.57471 0.0209589 0.00273794 -0.000517883 -0.126202 0.992001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.99149e-06 5.79257e-05 4 -9.29655e-05 3.93629 +EDGE_SE3:QUAT 607 1039 4.04912 1.18095 0.0361429 -0.0037455 0.000603697 0.0114315 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.02077e-05 0.00534229 4 3.14739e-05 3.99948 +EDGE_SE3:QUAT 608 1039 -0.23087 1.351 0.0157062 -0.00429601 0.00140661 0.0291213 0.999566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.67461e-05 0.0127388 3.99999 0.000192457 3.99665 +EDGE_SE3:QUAT 609 1039 -4.60203 1.39942 0.00199057 -0.00720847 0.00203424 0.0418214 0.999097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -7.01241e-05 0.0198438 3.99997 0.000438898 3.9931 +EDGE_SE3:QUAT 745 1039 5.74618 -1.13134 0.0350612 0.00650047 0.0122074 -0.995713 0.0914573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000289121 0.0264035 4.00045 0.0431063 0.0341029 +EDGE_SE3:QUAT 746 1039 1.57897 -1.00256 0.0102729 0.00419084 0.00980865 -0.995486 0.0943034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000171871 0.0170528 4.0001 0.0352352 0.0359596 +EDGE_SE3:QUAT 747 1039 -2.45375 -0.844647 -0.00715913 0.0050787 0.0063029 -0.996954 0.0775685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 9.23353e-05 0.0205211 4.00037 0.0217038 0.0242921 +EDGE_SE3:QUAT 748 1039 -6.66038 0.0721525 0.0426015 -0.000684159 -0.00913027 0.999958 0.000955119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.43556e-05 0.00273698 3.99967 0.0365248 0.000339064 +EDGE_SE3:QUAT 1040 1041 4.07055 -0.663942 0.00686132 0.00230551 0.00198836 -0.153785 0.9881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 3.44996e-06 0.0195338 3.99998 -0.00159607 3.9055 +EDGE_SE3:QUAT 608 1040 4.05168 1.027 0.0319264 -0.00165768 0.000320457 -0.0974054 0.995243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.9793e-09 0.000601895 4 2.73623e-06 3.96205 +EDGE_SE3:QUAT 609 1040 -0.327066 1.18108 0.0072756 -0.004892 0.000622945 -0.0844373 0.996417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 4.06376e-06 -2.98335e-06 4 7.06356e-05 3.97148 +EDGE_SE3:QUAT 610 1040 -4.76812 1.2619 -0.0306456 -0.00333281 -0.000771361 -0.0799864 0.99679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.50121e-05 -0.009297 3.99999 0.000413578 3.97443 +EDGE_SE3:QUAT 744 1040 5.76943 -1.49623 0.0178825 -0.00467623 -0.0129725 0.999061 0.0410764 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000202683 0.0187494 3.99956 0.0532055 0.00754601 +EDGE_SE3:QUAT 745 1040 1.52582 -1.33728 0.00259708 -0.00463097 -0.0102404 0.999347 0.034328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000175105 0.0185561 3.99985 0.042113 0.00524369 +EDGE_SE3:QUAT 746 1040 -2.68537 -1.24099 0.000466521 -0.00269592 -0.0075234 0.999452 0.0321361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.08982e-05 0.0107992 3.99986 0.0307084 0.00439609 +EDGE_SE3:QUAT 747 1040 -6.69644 -0.936556 -0.0244406 -0.00409853 -0.00367663 0.9988 0.0486662 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.23353e-05 0.0164492 4.00018 0.0162127 0.00960724 +EDGE_SE3:QUAT 1041 1042 4.01444 -0.709587 0.00477545 -0.00128543 0.00228721 -0.16334 0.986566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -2.44843e-05 0.0150957 3.99999 -0.00114414 3.89334 +EDGE_SE3:QUAT 609 1041 3.51856 -0.144697 0.0171756 -0.00237435 0.00152791 -0.2364 0.971652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.12773e-06 0.00472837 4 -0.000251896 3.77646 +EDGE_SE3:QUAT 610 1041 -0.893433 -0.0444512 -0.0118177 -0.000582432 0.000621785 -0.232124 0.972686 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.73086e-06 0.00301363 4 -0.000270912 3.78448 +EDGE_SE3:QUAT 611 1041 -5.29677 0.0499599 -0.00537485 -0.00166997 0.00325722 -0.230401 0.973089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -5.33686e-05 0.0195571 3.99999 -0.00199353 3.78776 +EDGE_SE3:QUAT 743 1041 5.92867 -0.756367 0.0220816 -0.00385595 -0.0110302 0.976978 0.21302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.38546e-05 0.015585 3.99949 0.0454652 0.182113 +EDGE_SE3:QUAT 744 1041 1.76307 -0.502236 0.00627845 -0.00454703 -0.0111348 0.980836 0.194463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.38683e-05 0.0185368 3.9995 0.0471881 0.151928 +EDGE_SE3:QUAT 745 1041 -2.48629 -0.39188 -0.00768941 -0.00496694 -0.00836698 0.982194 0.187618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.11994e-05 0.0204488 3.9998 0.0377518 0.141277 +EDGE_SE3:QUAT 746 1041 -6.66647 -0.313349 -0.000737054 -0.00326677 -0.00581433 0.982743 0.184854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.78446e-05 0.0134263 3.9999 0.0259603 0.136904 +EDGE_SE3:QUAT 1042 1043 4.03978 -0.709618 0.0262733 -0.000693781 0.000452067 -0.151959 0.988386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.90794e-07 0.00224635 4 -0.000135418 3.90764 +EDGE_SE3:QUAT 609 1042 6.75203 -2.62884 0.013205 -0.00302224 0.00370074 -0.391782 0.920046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.57936e-05 0.0103027 4.00001 -0.000604861 3.38604 +EDGE_SE3:QUAT 610 1042 2.36173 -2.49543 -0.0125833 -0.001299 0.00311992 -0.38778 0.921746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -4.79107e-05 0.014108 4.00001 -0.00194383 3.39855 +EDGE_SE3:QUAT 611 1042 -2.04219 -2.39103 -0.0202533 -0.00276112 0.00551262 -0.385937 0.922505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -0.000136725 0.0231058 4.00002 -0.00294116 3.40433 +EDGE_SE3:QUAT 612 1042 -6.49097 -2.27875 -0.032568 -0.00268882 0.00613381 -0.386293 0.922352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -0.000181386 0.0272824 4.00003 -0.00369057 3.40327 +EDGE_SE3:QUAT 742 1042 6.89461 1.12679 0.0434522 -0.00518692 -0.0133521 0.915361 0.40238 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.000323077 0.0181817 3.99934 0.0470476 0.648408 +EDGE_SE3:QUAT 743 1042 2.57908 1.55682 0.0268361 -0.00457852 -0.0121652 0.929029 0.369779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000240956 0.0167462 3.99943 0.0445344 0.547604 +EDGE_SE3:QUAT 744 1042 -1.65421 1.68993 0.0124084 -0.00523289 -0.0127358 0.935986 0.351769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000231047 0.0200059 3.99932 0.0487826 0.495754 +EDGE_SE3:QUAT 745 1042 -5.94555 1.73901 -0.0171257 -0.00587935 -0.0101424 0.938428 0.345276 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.56753e-05 0.0239942 3.99953 0.0432961 0.47754 +EDGE_SE3:QUAT 1043 1044 4.01907 -0.495425 0.0310367 0.00942357 0.00618801 -0.104598 0.994451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 0.000169482 0.0604421 3.99975 -0.00334255 3.95715 +EDGE_SE3:QUAT 611 1043 0.30148 -5.75731 -0.0268329 -0.00400872 0.00564788 -0.521901 0.852978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.55329e-05 0.00749436 4.00003 0.00208406 2.91044 +EDGE_SE3:QUAT 612 1043 -4.17448 -5.64829 -0.030567 -0.00419373 0.00635232 -0.521945 0.852945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -4.87613e-05 0.010039 4.00004 0.00176025 2.91026 +EDGE_SE3:QUAT 742 1043 4.7127 4.57421 0.0976533 -0.00385021 -0.0145809 0.843733 0.536551 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 -0.000296091 0.00245791 3.99986 0.0326458 1.15208 +EDGE_SE3:QUAT 743 1043 0.141069 4.84494 0.0705373 -0.00324562 -0.012987 0.862072 0.506609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 -0.000257758 0.00342741 3.99983 0.0315746 1.02705 +EDGE_SE3:QUAT 744 1043 -4.22888 4.87302 0.0555017 -0.00368066 -0.0140273 0.871656 0.489903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -0.00032867 0.00579752 3.99973 0.0363958 0.960562 +EDGE_SE3:QUAT 982 1043 0.165336 6.45359 0.118096 0.00210041 0.0155693 -0.902635 0.43012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -1.96459e-05 0.0202971 4.0007 0.0295352 0.740516 +EDGE_SE3:QUAT 1044 1045 4.36639 -0.44339 -0.0738444 -0.0027629 0.0315126 -0.0729737 0.996832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.01535 -0.00204917 0.2485 3.9963 -0.00917067 3.99408 +EDGE_SE3:QUAT 982 1044 -2.74561 3.65828 0.0964741 0.0101805 0.00991333 -0.942755 0.333183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 -0.000762066 0.0498456 4.00236 0.00495823 0.444761 +EDGE_SE3:QUAT 1045 1046 4.22245 -0.219073 0.0157738 0.00205056 -0.00165967 -0.0212357 0.999771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.4205e-05 -0.012746 3.99999 0.000133585 3.99824 +EDGE_SE3:QUAT 982 1045 -6.4 1.26305 -0.0857944 0.0382461 0.0237131 -0.963858 0.26259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99395 -0.00734991 0.171209 4.02788 0.00387066 0.283717 +EDGE_SE3:QUAT 1046 1047 3.99612 -0.11728 0.0397547 -0.00221382 0.000773388 -0.00535047 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.71246e-06 0.00604467 4 -1.60746e-05 3.99989 +EDGE_SE3:QUAT 1047 1048 4.43866 -0.114171 0.0371778 0.00174316 -0.00316517 -0.0020276 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -2.25093e-05 -0.0252795 3.99996 2.60347e-05 4.00014 +EDGE_SE3:QUAT 978 1047 3.10955 2.34153 0.0951782 0.00447831 0.010925 -0.999811 0.0154301 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000202267 0.0179229 3.99988 0.0431239 0.0014977 +EDGE_SE3:QUAT 979 1047 -1.22394 2.43069 0.0811201 0.00648363 0.00991622 -0.999865 0.0113552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000254226 0.0259427 4.00031 0.0390707 0.00106567 +EDGE_SE3:QUAT 980 1047 -5.35369 2.51162 0.0354941 0.00649911 0.00937907 -0.999875 0.0109618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000240063 0.0260039 4.00036 0.0369424 0.000990895 +EDGE_SE3:QUAT 1048 1049 4.11023 -0.08603 0.00628452 8.65201e-05 -0.0026216 0.000578436 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -8.11986e-07 -0.0209739 3.99997 -6.05224e-06 4.00011 +EDGE_SE3:QUAT 976 1048 6.93517 2.14655 0.112153 0.00513506 0.00872084 -0.999783 0.01821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.00017777 0.0205528 4.00016 0.0341107 0.00172302 +EDGE_SE3:QUAT 977 1048 2.94601 2.21931 0.0810137 0.00143591 0.00912204 -0.999828 0.0160993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.20781e-05 0.00574697 3.99971 0.0362787 0.00137416 +EDGE_SE3:QUAT 978 1048 -1.32881 2.32069 0.0959996 0.00130565 0.00885528 -0.999869 0.013493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.40125e-05 0.00522485 3.99972 0.0352631 0.00104602 +EDGE_SE3:QUAT 979 1048 -5.6776 2.44189 0.0594345 0.00343119 0.00802713 -0.999918 0.00941386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000112211 0.0137279 3.99994 0.0318442 0.000655134 +EDGE_SE3:QUAT 1049 1050 4.04784 -0.093814 0.0081726 -0.000397384 0.006587 -0.000629701 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -1.11316e-05 0.052701 3.99983 -1.7014e-05 4.00069 +EDGE_SE3:QUAT 975 1049 6.86683 2.01079 0.120561 0.00211088 0.00789344 -0.99975 0.020807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.43117e-05 0.00845035 3.99984 0.0311883 0.00199288 +EDGE_SE3:QUAT 976 1049 2.80817 2.08065 0.0881428 0.00231304 0.00811099 -0.999785 0.0189344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.21307e-05 0.00925848 3.99984 0.0320647 0.00171262 +EDGE_SE3:QUAT 977 1049 -1.11307 2.17673 0.0808077 -0.00119891 0.00886832 -0.999815 0.0170455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.22029e-05 -0.00479786 3.9997 0.0356097 0.00148508 +EDGE_SE3:QUAT 978 1049 -5.46067 2.30013 0.0976068 -0.00115228 0.00854148 -0.999868 0.0137615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.16575e-05 -0.00461067 3.99972 0.0342755 0.00105661 +EDGE_SE3:QUAT 1050 1051 4.04593 -0.0983052 0.06121 0.00154249 0.00560638 -0.00178515 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 3.32916e-05 0.0448887 3.99987 -3.89243e-05 4.00049 +EDGE_SE3:QUAT 974 1050 6.86371 1.8342 0.0478302 -0.000438607 0.00803734 -0.999774 0.0196522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.9646e-06 -0.00175505 3.99974 0.0321862 0.00180471 +EDGE_SE3:QUAT 975 1050 2.78391 1.93075 0.109343 0.0083665 0.00835686 -0.999725 0.0202384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000255399 0.0334888 4.00091 0.0320509 0.00217572 +EDGE_SE3:QUAT 976 1050 -1.26971 2.01702 0.0762304 0.00883053 0.00862983 -0.999762 0.0180001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000280587 0.0353416 4.00102 0.0332337 0.0018845 +EDGE_SE3:QUAT 977 1050 -5.21531 2.13081 0.0930314 0.00533402 0.00929027 -0.999813 0.0161052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000197564 0.021347 4.00015 0.0364545 0.00148375 +EDGE_SE3:QUAT 1051 1052 4.28557 -0.097132 0.0505174 -0.000936425 -0.00550995 -0.0028209 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 1.86089e-05 -0.0441154 3.99988 6.15739e-05 4.00045 +EDGE_SE3:QUAT 973 1051 6.8352 1.62567 0.0626719 0.00404052 0.00713992 -0.999896 0.0118449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000115341 0.0161666 4.00007 0.0281688 0.000824946 +EDGE_SE3:QUAT 974 1051 2.83638 1.77603 0.103149 0.00505574 0.00652865 -0.999804 0.017968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000126488 0.0202339 4.00027 0.0253702 0.00155474 +EDGE_SE3:QUAT 975 1051 -1.22915 1.86914 0.0942762 0.0140322 0.00668377 -0.999711 0.018364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99919 0.00029391 0.0561544 4.00305 0.0246779 0.00228985 +EDGE_SE3:QUAT 976 1051 -5.31776 1.97523 0.0605486 0.0144521 0.00722369 -0.999739 0.0161704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99914 0.000342705 0.0578282 4.00321 0.0270372 0.00206494 +EDGE_SE3:QUAT 1052 1053 4.07018 -0.116026 0.011961 -0.000661596 -0.00466377 -0.00409886 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 1.02171e-05 -0.0373446 3.99991 7.62283e-05 4.00028 +EDGE_SE3:QUAT 972 1052 7.04754 1.50255 0.0927064 0.00569252 0.00785254 -0.999932 0.00641087 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000176923 0.0227731 4.00029 0.0311197 0.000536147 +EDGE_SE3:QUAT 973 1052 2.54676 1.61355 0.0756229 -0.00155529 0.00796877 -0.999922 0.00950406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.5224e-05 -0.00622251 3.99978 0.0319855 0.000626793 +EDGE_SE3:QUAT 974 1052 -1.47774 1.72267 0.112155 -0.000484189 0.00764737 -0.999862 0.0147275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.95733e-06 -0.00193731 3.99977 0.0306291 0.00110314 +EDGE_SE3:QUAT 975 1052 -5.56017 1.807 0.0235749 0.00842167 0.00753725 -0.999822 0.015093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000234381 0.0336996 4.00095 0.029126 0.00140725 +EDGE_SE3:QUAT 1053 1054 4.29688 -0.103026 -0.00059886 0.0015644 0.00775342 -0.00199659 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 4.5713e-05 0.0620774 3.99976 -5.9763e-05 4.00095 +EDGE_SE3:QUAT 971 1053 7.19901 1.45388 0.0761462 -0.00014869 0.00734788 -0.999972 0.00142527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.75478e-06 -0.000594807 3.99978 0.0293923 0.000224203 +EDGE_SE3:QUAT 972 1053 2.97004 1.55892 0.0603195 0.000908808 0.00843688 -0.999961 0.00238907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.19763e-05 0.00363566 3.99973 0.0337286 0.000310561 +EDGE_SE3:QUAT 973 1053 -1.50599 1.64656 0.104221 -0.00620673 0.00877648 -0.999928 0.00529673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000219509 -0.0248304 4.00029 0.0353724 0.000579133 +EDGE_SE3:QUAT 974 1053 -5.57012 1.70898 0.130101 -0.00516467 0.00775628 -0.999897 0.010911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000161701 -0.020664 4.00017 0.0314701 0.000830558 +EDGE_SE3:QUAT 1054 1055 4.03555 -0.0900812 0.0485064 0.000876705 0.00231071 -0.000252116 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 8.07309e-06 0.0184887 3.99998 -2.21852e-06 4.00009 +EDGE_SE3:QUAT 971 1054 2.90541 1.54339 0.0735964 -0.00757605 -0.00573829 0.999955 0.000452817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000174527 0.0303049 4.00079 0.0229875 0.000362494 +EDGE_SE3:QUAT 972 1054 -1.3218 1.64199 0.046076 0.00894628 0.00698671 -0.999935 0.000603784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000249351 0.0357863 4.00109 0.0279152 0.00051638 +EDGE_SE3:QUAT 973 1054 -5.79728 1.7131 0.16044 0.00162393 0.00695151 -0.99997 0.00302267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.6123e-05 0.00649627 3.99985 0.0277659 0.00023984 +EDGE_SE3:QUAT 1055 1056 4.10024 -0.0879453 0.0491941 0.000344184 -0.00135431 0.000378337 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.84827e-06 -0.0108361 3.99999 -2.03483e-06 4.00003 +EDGE_SE3:QUAT 970 1055 3.37637 1.54257 0.0762413 -0.00544676 -0.00674589 0.999958 0.00288952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000148006 0.0217885 4.00029 0.0271127 0.000335838 +EDGE_SE3:QUAT 971 1055 -1.10437 1.65047 0.0666756 -0.0101379 -0.0051031 0.999935 0.00103943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000209571 0.0405513 4.00154 0.020508 0.000520548 +EDGE_SE3:QUAT 972 1055 -5.34133 1.73668 0.0376838 0.0113994 0.00685822 -0.999911 0.000294476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.00031245 0.0455979 4.00189 0.027425 0.0007081 +EDGE_SE3:QUAT 1056 1057 4.26932 -0.123501 0.0227123 0.00366747 -0.00433539 -0.00188125 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -6.42573e-05 -0.0346017 3.99993 3.41758e-05 4.00029 +EDGE_SE3:QUAT 969 1056 3.39026 1.5457 0.075794 1.90955e-05 -0.0119467 0.999923 0.00326178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.63588e-06 -7.64472e-05 3.99943 0.0477816 0.000613416 +EDGE_SE3:QUAT 970 1056 -0.732057 1.65793 0.0856211 -0.00420997 -0.00645853 0.999968 0.00199912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000108955 0.0168409 4.00011 0.0259032 0.000254625 +EDGE_SE3:QUAT 971 1056 -5.19194 1.75619 0.044793 -0.00874741 -0.00479608 0.99995 0.000629302 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000169024 0.0349895 4.00113 0.0192362 0.000400142 +EDGE_SE3:QUAT 1057 1058 4.34203 -0.0867559 -0.000950189 -0.00557641 0.00332662 -0.0103465 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -7.42562e-05 0.0259161 3.99996 -0.000134303 3.99974 +EDGE_SE3:QUAT 968 1057 3.23597 1.66992 0.0186572 0.00203224 0.00551237 0.999965 0.00591014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.39339e-05 -0.00812975 3.99994 -0.0221438 0.000278835 +EDGE_SE3:QUAT 969 1057 -0.868927 1.70304 0.104245 0.00431121 -0.00843063 0.999943 0.00489769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000145948 -0.0172471 4.00002 0.0335539 0.000451779 +EDGE_SE3:QUAT 970 1057 -4.97055 1.79587 0.0746438 -0.000238748 -0.00332472 0.999988 0.00358054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.86265e-06 0.000955024 3.99996 0.0133052 9.57674e-05 +EDGE_SE3:QUAT 1058 1059 4.3345 -0.259712 0.0615423 0.0018175 -0.0150919 -0.0689262 0.997506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00349 -0.000473856 -0.118467 3.99915 0.00407479 3.9845 +EDGE_SE3:QUAT 966 1058 6.71328 2.63634 0.172619 0.0222568 0.00839964 -0.993779 0.108801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99788 -0.000597322 0.0906505 4.00836 0.0134884 0.0494786 +EDGE_SE3:QUAT 967 1058 2.93423 1.79051 0.066485 0.00490851 0.00780845 -0.99988 0.0124093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000151846 0.0196401 4.00016 0.0307379 0.00094863 +EDGE_SE3:QUAT 968 1058 -1.08774 1.80524 0.0388496 -0.001636 -8.39428e-05 0.999856 0.0169103 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.63157e-06 0.00654679 4.00004 0.000556799 0.00115463 +EDGE_SE3:QUAT 969 1058 -5.20962 1.83752 0.147713 0.00130465 -0.0140457 0.999779 0.0155805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.69136e-05 -0.00522278 3.99925 0.0559815 0.00176165 +EDGE_SE3:QUAT 1059 1060 4.22624 -0.732402 0.0247691 -0.000341414 -0.00422897 -0.1738 0.984772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -6.73004e-05 -0.0330101 3.99994 0.00284418 3.87945 +EDGE_SE3:QUAT 965 1059 5.96536 3.0897 0.0696494 0.00865338 0.010096 -0.983706 0.179292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 -2.16754e-06 0.0367036 4.00149 0.0251746 0.1291 +EDGE_SE3:QUAT 966 1059 2.42205 1.95595 0.0341636 0.0066156 0.00622712 -0.999163 0.039885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000131204 0.026529 4.00062 0.0227074 0.0066686 +EDGE_SE3:QUAT 967 1059 -1.39795 1.94302 0.0911358 0.0109538 -0.00595257 0.998343 0.0561824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 -0.000102903 -0.044028 4.00194 0.0187269 0.0132001 +EDGE_SE3:QUAT 968 1059 -5.39017 2.23781 0.094716 0.0134457 0.00139554 0.996231 0.0856845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 0.000432275 -0.0543632 4.00275 -0.0146454 0.0301652 +EDGE_SE3:QUAT 1060 1061 4.1512 -0.972752 0.00429874 0.00521249 -0.000278362 -0.223687 0.974647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 3.61358e-05 0.0114629 3.99998 -0.00180934 3.79989 +EDGE_SE3:QUAT 964 1060 4.8752 3.5243 0.0489865 0.00470093 0.0110244 -0.977585 0.210199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000129305 0.0208267 4.00047 0.0317538 0.17712 +EDGE_SE3:QUAT 965 1060 1.74485 2.27491 0.0216027 0.00232514 0.0107749 -0.999923 0.00564663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000104658 0.00930266 3.99963 0.04299 0.000611261 +EDGE_SE3:QUAT 966 1060 -1.83255 2.33493 0.0130861 -0.00107384 -0.00739959 0.990904 0.134364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.77476e-05 0.00426641 3.99978 0.0294035 0.0724399 +EDGE_SE3:QUAT 967 1060 -5.50984 3.13521 0.222356 0.0158933 -0.00455099 0.973353 0.228715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99917 0.00116745 -0.0687959 4.0041 -0.0117215 0.210517 +EDGE_SE3:QUAT 1061 1062 4.06471 -0.805495 0.00702686 -0.000820004 0.00186283 -0.1758 0.984424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.61858e-05 0.012523 3.99999 -0.00102948 3.87642 +EDGE_SE3:QUAT 963 1061 3.69021 3.47565 -0.0109735 0.00179278 0.00124327 -0.981513 0.191385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.91763e-06 0.00762388 4.00006 0.00187925 0.146528 +EDGE_SE3:QUAT 964 1061 0.662106 2.70979 0.0149426 -0.00301139 -0.00652702 0.999873 0.0142163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.66217e-05 0.0120498 3.99996 0.0264379 0.0010195 +EDGE_SE3:QUAT 965 1061 -2.40875 3.18943 0.0284182 0.000275719 -0.0056918 0.975897 0.218157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.60357e-05 -0.00165174 3.99993 0.0196456 0.190474 +EDGE_SE3:QUAT 966 1061 -5.58147 4.38523 0.0261898 0.00112784 -0.00222806 0.935843 0.352408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.25066e-06 -0.00605066 4.00004 0.00348408 0.496782 +EDGE_SE3:QUAT 1062 1063 4.24875 -0.609744 -0.00949593 0.00435979 0.001494 -0.106265 0.994327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.11676e-05 0.0172677 3.99998 -0.00101193 3.9549 +EDGE_SE3:QUAT 961 1062 5.31401 4.77682 0.00664707 -0.000823085 0.00199756 -0.907671 0.419678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.54645e-06 -0.0028598 3.99999 0.00697444 0.704536 +EDGE_SE3:QUAT 962 1062 2.82187 2.97306 -0.00467363 -0.00214805 0.00605679 -0.979351 0.202065 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.44296e-06 -0.0087025 3.99985 0.0251198 0.163505 +EDGE_SE3:QUAT 963 1062 -0.378771 2.67647 -0.0172536 0.00339779 0.00258525 -0.999863 0.0159892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.14238e-05 0.0135965 4.00016 0.00990047 0.00109336 +EDGE_SE3:QUAT 964 1062 -3.31254 3.59308 0.0112761 -0.00392967 -0.00800372 0.981862 0.189388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.01788e-05 0.0161076 3.99977 0.03492 0.143852 +EDGE_SE3:QUAT 1063 1064 4.09388 -0.241907 0.0110448 -0.00100625 -3.71153e-05 -0.0270163 0.999634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.64877e-07 -0.000622661 4 9.87832e-06 3.99708 +EDGE_SE3:QUAT 960 1063 5.38818 3.44534 0.000161395 -0.00253858 0.00350777 -0.849368 0.527784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.02875e-05 -0.00930412 3.99994 0.0130108 1.11431 +EDGE_SE3:QUAT 961 1063 2.07894 1.91804 -0.0019494 0.00203383 -0.00147062 -0.947056 0.321059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.72115e-05 0.00890372 4.00001 -0.00910797 0.412358 +EDGE_SE3:QUAT 962 1063 -1.31158 1.84126 -0.00410645 -0.000635356 0.00152154 -0.995284 0.0969877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.4933e-06 -0.00256593 3.99999 0.00643182 0.0376386 +EDGE_SE3:QUAT 963 1063 -4.64804 3.15713 -0.0548268 -0.00462345 0.00128727 0.995879 0.0905601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 2.38963e-05 0.0187273 4.00035 -0.00172178 0.0328937 +EDGE_SE3:QUAT 1064 1065 4.09879 -0.0887043 0.0216813 0.00122398 -0.000799099 0.000598013 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.91032e-06 -0.00640157 4 -1.8962e-06 4.00001 +EDGE_SE3:QUAT 960 1064 3.34764 -0.118545 0.0167527 -0.00306464 0.00447826 -0.863365 0.50455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.5644e-05 -0.0113706 3.99991 0.016812 1.01842 +EDGE_SE3:QUAT 961 1064 -1.31628 -0.384085 -0.00243648 0.00191145 -0.000570616 -0.955382 0.295366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.01919e-05 0.00846163 4.00003 -0.00592281 0.348993 +EDGE_SE3:QUAT 962 1064 -5.39346 1.31409 0.00965124 -0.000583075 0.00284847 -0.997566 0.0696684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.26975e-06 -0.00234153 3.99997 0.0115792 0.0194498 +EDGE_SE3:QUAT 1065 1066 4.31926 -0.0780797 0.0186118 -0.000958321 -0.00176911 -0.00435872 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 6.48437e-06 -0.0142028 3.99999 3.09177e-05 3.99997 +EDGE_SE3:QUAT 959 1065 6.56846 -2.39977 0.0886956 0.00328167 -0.00291021 -0.760535 0.649282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.19926e-05 0.0120281 3.99995 -0.0112483 1.68637 +EDGE_SE3:QUAT 960 1065 1.25117 -3.63171 0.0429258 -0.00313145 0.00277575 -0.863001 0.505185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.72289e-06 -0.0134646 3.99995 0.0141167 1.02096 +EDGE_SE3:QUAT 961 1065 -4.74118 -2.60393 0.0119032 0.00131571 -0.00217972 -0.955236 0.295834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.03445e-07 0.00545578 3.99998 -0.00971213 0.350105 +EDGE_SE3:QUAT 1066 1067 3.98717 -0.308611 -0.000251049 -0.00203295 0.0121314 -0.0923911 0.995647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00217 -0.00040398 0.0936129 3.99949 -0.0042838 3.96804 +EDGE_SE3:QUAT 960 1066 -0.924988 -7.35882 0.0787189 -0.005123 0.0026753 -0.865387 0.501072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -7.16857e-05 -0.0239475 3.99998 0.0199905 1.00457 +EDGE_SE3:QUAT 1067 1068 4.06434 -0.843384 0.00828126 -0.00127831 0.00123911 -0.217279 0.976108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.8504e-06 0.00599116 4 -0.000504015 3.81117 +EDGE_SE3:QUAT 1068 1069 3.97144 -0.949047 0.00868671 -0.00126367 6.76613e-06 -0.21835 0.97587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.19339e-06 -0.00315552 4 0.000465001 3.8093 +EDGE_SE3:QUAT 427 1068 1.73308 -6.95276 0.0413465 -0.00714069 0.00147709 0.677079 0.735874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 0.000305027 0.0450013 4.00005 0.0196069 2.16676 +EDGE_SE3:QUAT 1069 1070 3.9968 -0.710154 0.00438339 0.00446924 -8.88408e-05 -0.142882 0.98973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.96458e-05 0.00686945 3.99999 -0.000673686 3.91835 +EDGE_SE3:QUAT 427 1069 3.04002 -3.09139 0.0138332 -0.00821482 -0.00103618 0.500191 0.865875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -6.05402e-05 0.035703 3.99987 0.0132004 2.99953 +EDGE_SE3:QUAT 428 1069 -2.26839 -3.12038 0.0190507 -0.005755 0.00139934 0.376328 0.926468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 3.67787e-06 0.0324396 3.99993 0.00754987 3.43377 +EDGE_SE3:QUAT 429 1069 -6.85472 -2.27828 -0.227969 -0.00997877 -0.016252 0.296837 0.954738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00108 0.00125486 -0.0797431 3.99999 -0.00922781 3.64903 +EDGE_SE3:QUAT 1070 1071 3.99185 -0.419401 -0.0284696 0.00141981 0.0139129 -0.0770139 0.996932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00311 -0.000281251 0.111698 3.99924 -0.0043074 3.97939 +EDGE_SE3:QUAT 427 1070 5.62787 0.037958 0.000461746 -0.00405566 -0.00022232 0.370876 0.928674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.32918e-05 0.0149701 3.99998 0.00390529 3.44986 +EDGE_SE3:QUAT 428 1070 1.10314 -0.851045 -0.000321507 -0.00167395 0.00205488 0.240179 0.970725 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.5997e-05 0.0196767 3.99998 0.00249624 3.76935 +EDGE_SE3:QUAT 429 1070 -3.16275 -0.61454 -0.103944 -0.00323137 -0.0162573 0.157616 0.987361 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00351 0.00107313 -0.119316 3.99926 -0.00915515 3.90418 +EDGE_SE3:QUAT 1071 1072 4.27731 -0.2369 0.00871919 -0.000874412 0.0042884 -0.0259605 0.999653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -2.61282e-05 0.0340024 3.99993 -0.000440496 3.99759 +EDGE_SE3:QUAT 428 1071 4.84716 0.653917 -0.04126 -0.00389815 0.0159363 0.164218 0.986288 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00416 0.00079053 0.130033 3.99905 0.0107483 3.89635 +EDGE_SE3:QUAT 429 1071 0.758991 0.244937 0.0032844 -0.00291809 -0.00253938 0.0806271 0.996737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.35764e-05 -0.0173062 3.99998 -0.00065745 3.97407 +EDGE_SE3:QUAT 430 1071 -3.66019 0.369061 -0.0364414 -0.000849653 -0.00456264 0.0486921 0.998803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 3.88702e-05 -0.0358781 3.99992 -0.000869008 3.99084 +EDGE_SE3:QUAT 1072 1073 4.02493 -0.0848876 0.0341119 -0.00172132 -0.00334485 -0.000780331 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 2.28424e-05 -0.0267758 3.99996 9.98764e-06 4.00018 +EDGE_SE3:QUAT 429 1072 5.01784 0.700991 0.0302949 -0.00405061 0.00173361 0.0547743 0.998489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.99088e-05 0.0164635 3.99998 0.000474252 3.98807 +EDGE_SE3:QUAT 430 1072 0.610632 0.550929 0.0119337 -0.00193642 -0.000443567 0.0227944 0.999738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.83251e-06 -0.00301627 4 -3.23613e-05 3.99792 +EDGE_SE3:QUAT 431 1072 -3.54424 0.651623 0.0401101 0.00197332 0.00649792 0.0172245 0.999829 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 6.79884e-05 0.0515596 3.99984 0.000444976 3.99948 +EDGE_SE3:QUAT 1073 1074 4.19879 -0.0659609 0.0025063 -0.0021971 -0.00393127 0.00128867 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 3.49841e-05 -0.0314176 3.99994 -2.10529e-05 4.00024 +EDGE_SE3:QUAT 430 1073 4.61117 0.657166 0.0474718 -0.00323669 -0.0037376 0.0217236 0.999752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 5.34929e-05 -0.029037 3.99995 -0.000313342 3.99832 +EDGE_SE3:QUAT 431 1073 0.464953 0.705535 0.0200551 0.000531283 0.00289121 0.0161626 0.999865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 9.32384e-06 0.0230182 3.99997 0.000185837 3.99909 +EDGE_SE3:QUAT 432 1073 -3.79914 0.809436 0.047742 0.00227455 0.004249 0.0118484 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 4.32233e-05 0.0336633 3.99993 0.000199783 3.99972 +EDGE_SE3:QUAT 1074 1075 4.16492 -0.0928737 0.0210239 2.44605e-05 -0.00939376 7.23347e-05 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00141 -7.66982e-07 -0.0751733 3.99965 -2.66952e-06 4.00141 +EDGE_SE3:QUAT 431 1074 4.635 0.769525 -0.00190242 -0.00159773 -0.00117692 0.0177019 0.999841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 7.71115e-06 -0.00907164 3.99999 -7.93296e-05 3.99877 +EDGE_SE3:QUAT 432 1074 0.369107 0.828383 0.0109331 -0.000125001 1.75979e-05 0.0132194 0.999913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.03272e-08 0.000160573 4 1.10494e-06 3.9993 +EDGE_SE3:QUAT 433 1074 -3.99514 0.94273 0.0613642 -0.00020225 0.00874715 0.00834676 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 8.25203e-06 0.0700089 3.99969 0.000292055 4.00095 +EDGE_SE3:QUAT 1075 1076 4.18749 -0.107213 0.010419 0.0040416 0.00787455 -0.002438 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00093 0.000124088 0.0631263 3.99975 -7.10144e-05 4.00097 +EDGE_SE3:QUAT 432 1075 4.53912 0.841467 0.0332081 0.000207336 -0.00911112 0.0133207 0.99987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00133 1.89927e-05 -0.0729239 3.99967 -0.000485739 4.00062 +EDGE_SE3:QUAT 433 1075 0.176288 0.926916 0.0106986 0.000170938 -0.000469959 0.00853007 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.77746e-07 -0.00377676 4 -1.61314e-05 3.99971 +EDGE_SE3:QUAT 434 1075 -4.25822 1.04408 -0.084825 -0.00408401 -0.00868045 0.00391002 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00113 0.000148465 -0.0692668 3.9997 -0.000142753 4.00114 +EDGE_SE3:QUAT 1076 1077 4.24278 -0.107816 0.031745 0.00229147 0.000273432 -0.00179629 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.57833e-06 0.00223682 4 -2.01951e-06 3.99999 +EDGE_SE3:QUAT 433 1076 4.36067 0.885717 0.0273361 0.00429581 0.00757901 0.00596555 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 0.000137601 0.0603316 3.99977 0.000185629 4.00077 +EDGE_SE3:QUAT 434 1076 -0.0654207 0.965271 0.00806316 -0.000270492 -0.000844226 0.00177503 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 9.42712e-07 -0.00674803 4 -5.99193e-06 4 +EDGE_SE3:QUAT 435 1076 -4.36258 1.07348 -0.0320563 -0.00104858 -0.00110942 -0.00128213 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.62658e-06 -0.00889147 4 5.67245e-06 4.00001 +EDGE_SE3:QUAT 1077 1078 4.16351 -0.102304 0.0203391 0.000900847 -0.00229668 -0.000945529 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -8.38987e-06 -0.0183635 3.99998 8.79443e-06 4.00008 +EDGE_SE3:QUAT 434 1077 4.1641 0.881288 0.0408726 0.00224945 -0.000516126 -7.97277e-05 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.64125e-06 -0.00412683 4 1.78852e-07 4 +EDGE_SE3:QUAT 435 1077 -0.133626 0.95471 0.00855681 0.00122352 -0.000784413 -0.00319418 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.84729e-06 -0.00622831 4 9.94008e-06 3.99997 +EDGE_SE3:QUAT 436 1077 -4.3298 1.06624 -0.0125219 0.000605817 0.00117405 -0.00678405 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.6385e-06 0.00944109 3.99999 -3.20597e-05 3.99984 +EDGE_SE3:QUAT 1078 1079 4.09612 -0.0929668 -0.0176591 -0.000876647 0.00285223 -0.000921164 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.01768e-05 0.0228088 3.99997 -1.06757e-05 4.00013 +EDGE_SE3:QUAT 435 1078 4.03173 0.830445 0.0358686 0.00180173 -0.00313272 -0.00412861 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -2.34392e-05 -0.0249726 3.99996 5.19164e-05 4.00009 +EDGE_SE3:QUAT 436 1078 -0.154691 0.915587 0.00288332 0.00119313 -0.0012668 -0.0076699 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -6.24832e-06 -0.0100238 3.99999 3.83449e-05 3.99979 +EDGE_SE3:QUAT 437 1078 -4.36023 1.0187 0.00709405 0.0015212 -0.00243427 -0.0101582 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.60452e-05 -0.0192861 3.99998 9.78559e-05 3.99968 +EDGE_SE3:QUAT 1079 1080 4.2802 -0.0911054 0.0155852 -0.00120316 0.00796807 -0.000120748 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -3.8564e-05 0.0637568 3.99975 -5.68558e-06 4.00102 +EDGE_SE3:QUAT 436 1079 3.92587 0.759771 -0.00192881 0.000192802 0.0017179 -0.00869688 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 7.09989e-07 0.0137619 3.99999 -5.98578e-05 3.99974 +EDGE_SE3:QUAT 437 1079 -0.278321 0.845211 0.0104774 0.000500919 0.000502362 -0.011138 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.59476e-07 0.0040851 4 -2.28698e-05 3.99951 +EDGE_SE3:QUAT 438 1079 -4.49818 0.94828 -0.0624951 0.00241895 -0.00718214 -0.0136446 0.999878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 -8.55863e-05 -0.0570546 3.9998 0.000391477 4.00007 +EDGE_SE3:QUAT 1080 1081 3.99168 -0.0966537 0.0378237 -0.000189351 -0.000623147 -0.000463177 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.6779e-07 -0.00498624 4 1.15308e-06 4.00001 +EDGE_SE3:QUAT 437 1080 3.99424 0.646307 0.0229772 -0.000416587 0.00832661 -0.0117112 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00111 -3.33305e-05 0.0665567 3.99972 -0.000390564 4.00056 +EDGE_SE3:QUAT 438 1080 -0.220882 0.732697 0.0169527 0.00144309 0.000585306 -0.0141421 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.48696e-06 0.0049259 4 -3.53924e-05 3.99921 +EDGE_SE3:QUAT 439 1080 -4.51254 0.836465 -0.0200899 0.000830074 0.00102073 -0.0161235 0.999869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.06087e-06 0.00832325 4 -6.75024e-05 3.99898 +EDGE_SE3:QUAT 1081 1082 4.38003 -0.079376 0.0261833 -0.00158201 -0.00616397 0.000127802 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 3.91403e-05 -0.0493157 3.99985 -4.59526e-06 4.00061 +EDGE_SE3:QUAT 438 1081 3.77093 0.532376 0.042684 0.00134593 -7.1671e-05 -0.0139921 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.83775e-07 -0.000347239 4 1.90197e-06 3.99922 +EDGE_SE3:QUAT 439 1081 -0.523084 0.621582 0.00733803 0.00074898 0.000447879 -0.0164863 0.999864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.33054e-06 0.00372972 4 -3.1144e-05 3.99892 +EDGE_SE3:QUAT 440 1081 -4.61082 0.73482 0.0404555 0.00232513 0.00601653 -0.022296 0.999731 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 3.71471e-05 0.0487242 3.99985 -0.000543505 3.9986 +EDGE_SE3:QUAT 1082 1083 4.08606 -0.0883322 0.0144926 0.00120172 -0.00681027 0.000279446 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 -3.24495e-05 -0.0544949 3.99981 -6.27998e-06 4.00074 +EDGE_SE3:QUAT 439 1082 3.84011 0.397086 0.0321308 -0.000978845 -0.00556691 -0.0159022 0.999858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 1.00157e-05 -0.04471 3.99987 0.000355328 3.99949 +EDGE_SE3:QUAT 440 1082 -0.246383 0.450733 0.0112491 0.000815339 -4.11769e-05 -0.0212606 0.999774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.13476e-08 -0.000121239 4 5.50935e-07 3.99819 +EDGE_SE3:QUAT 441 1082 -4.29812 0.538641 0.0579573 -0.00110013 0.00721333 -0.0231411 0.999706 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -6.01464e-05 0.0573651 3.9998 -0.00066411 3.99868 +EDGE_SE3:QUAT 1083 1084 4.32642 -0.124728 -0.0130855 0.00211899 0.00169766 -0.0122429 0.999921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.39481e-05 0.0138895 3.99999 -8.55039e-05 3.99945 +EDGE_SE3:QUAT 440 1083 3.81625 0.185891 0.0283443 0.00158256 -0.00679273 -0.0213113 0.999749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -6.58735e-05 -0.0539085 3.99982 0.000574867 3.99891 +EDGE_SE3:QUAT 441 1083 -0.233423 0.254379 0.00892645 -6.14049e-05 0.000435799 -0.0229125 0.999737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.0979e-07 0.00346677 4 -3.96416e-05 3.9979 +EDGE_SE3:QUAT 442 1083 -4.47951 0.221603 -0.000238588 -0.00194655 -0.0017759 -0.000110536 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.3823e-05 -0.0142099 3.99999 6.38041e-07 4.00005 +EDGE_SE3:QUAT 1084 1085 4.34214 -0.335504 0.00635974 -0.00316001 0.0182788 -0.0846033 0.996242 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00497 -0.000869724 0.14162 3.99881 -0.00596778 3.97638 +EDGE_SE3:QUAT 441 1084 4.08743 -0.0473747 0.00112932 0.00192186 0.00196947 -0.0348782 0.999388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.26319e-05 0.0165309 3.99998 -0.000292611 3.9952 +EDGE_SE3:QUAT 442 1084 -0.142222 0.105781 0.00765942 0.000158031 -0.000104766 -0.0119258 0.999929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.68343e-08 -0.000815336 4 4.81651e-06 3.99943 +EDGE_SE3:QUAT 443 1084 -4.16298 -0.0903312 -0.164787 0.00081267 -0.0182727 0.0426755 0.998922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00535 0.000283217 -0.14637 3.99867 -0.00312776 3.99806 +EDGE_SE3:QUAT 1085 1086 4.02888 -0.610589 0.0143941 -0.00382369 -0.00346396 -0.150267 0.988632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 8.59431e-06 -0.0335712 3.99993 0.00266993 3.90996 +EDGE_SE3:QUAT 442 1085 4.19212 -0.349598 0.0132371 -0.00259121 0.0181466 -0.0967538 0.99514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00489 -0.000908647 0.140295 3.99885 -0.00674766 3.96747 +EDGE_SE3:QUAT 443 1085 0.203127 -0.0614578 0.00492479 -0.00169984 -0.000113072 -0.0420639 0.999113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.69882e-06 -0.00175918 4 4.29959e-05 3.99292 +EDGE_SE3:QUAT 444 1085 -3.97724 -0.6025 0.00827168 0.00361889 0.0033912 0.0850113 0.996368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 5.79939e-05 0.0231621 3.99997 0.000928903 3.97123 +EDGE_SE3:QUAT 1086 1087 4.01973 -0.733205 0.00275496 0.00162603 0.000449958 -0.169856 0.985467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.96451e-06 0.00669555 4 -0.000657899 3.88461 +EDGE_SE3:QUAT 443 1086 4.1403 -1.02053 0.0215629 -0.00561261 -0.00352099 -0.191607 0.981449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 2.1557e-05 -0.0392225 3.9999 0.00411642 3.85353 +EDGE_SE3:QUAT 444 1086 0.0874594 -0.528011 -0.0073582 -0.000550534 -0.000174978 -0.0653829 0.99786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.66903e-07 -0.00182158 4 6.41582e-05 3.9829 +EDGE_SE3:QUAT 445 1086 -3.81564 -1.19368 -0.0130842 -0.00362729 0.000555836 0.114741 0.993389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.69237e-05 0.00930963 3.99999 0.000627814 3.94736 +EDGE_SE3:QUAT 1087 1088 3.96541 -0.714703 0.00498852 0.00444703 0.00346646 -0.168585 0.985671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 1.16262e-05 0.0353857 3.99992 -0.00320007 3.88663 +EDGE_SE3:QUAT 398 1087 4.82273 4.61626 0.0413481 0.00348524 0.00925884 -0.939603 0.342124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -4.61291e-05 0.0191306 4.00049 0.0182339 0.468417 +EDGE_SE3:QUAT 399 1087 0.659575 4.73617 0.0202429 -0.000147213 0.0103422 -0.936852 0.349573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000147502 0.00284857 3.99992 0.029648 0.489079 +EDGE_SE3:QUAT 400 1087 -3.64153 4.79127 0.0145975 -0.00115505 0.0113365 -0.933263 0.359012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000199734 -0.0012257 3.99979 0.0343024 0.51592 +EDGE_SE3:QUAT 444 1087 3.98615 -1.7909 -0.000147023 0.00119303 0.000329103 -0.233842 0.972274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.74629e-06 0.00564559 4 -0.000781587 3.78128 +EDGE_SE3:QUAT 445 1087 0.263984 -1.00263 -0.0090407 -0.00209331 0.000576298 -0.0555163 0.998455 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.10904e-06 0.00319737 4 -7.56618e-05 3.98767 +EDGE_SE3:QUAT 446 1087 -3.44066 -1.82261 -0.0458469 -0.00245309 -0.00278249 0.187734 0.982213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.74778e-05 -0.015697 3.99999 -0.00126317 3.85908 +EDGE_SE3:QUAT 447 1087 -6.05084 -4.41185 -0.214324 -0.00540554 -0.0172819 0.439429 0.898095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00108 0.00152242 -0.0753564 4.00038 -0.0111871 3.2288 +EDGE_SE3:QUAT 1088 1089 4.08461 -0.751881 -0.0261016 0.00432918 0.00855619 -0.144821 0.989411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00128 -0.000125489 0.0737471 3.99967 -0.00546475 3.91747 +EDGE_SE3:QUAT 397 1088 5.4563 2.52158 -0.0211677 -0.00733807 0.00988411 -0.983322 0.181457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000241679 -0.0302991 3.99989 0.0466243 0.132499 +EDGE_SE3:QUAT 398 1088 1.32006 2.61 0.00996073 0.00666266 0.0067281 -0.983853 0.17873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -3.31303e-05 0.0282024 4.00087 0.0155692 0.128048 +EDGE_SE3:QUAT 399 1088 -2.80025 2.6767 0.0162931 0.00333521 0.00741342 -0.98244 0.186399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 6.85645e-05 0.0144019 4.00021 0.022311 0.139165 +EDGE_SE3:QUAT 445 1088 4.12448 -2.15644 -0.00562252 0.00249391 0.00360981 -0.22316 0.974772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -4.60976e-05 0.0332071 3.99994 -0.00386971 3.80107 +EDGE_SE3:QUAT 446 1088 0.507986 -1.02911 -0.0050092 0.00190308 0.00105039 0.0195033 0.999807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.89924e-06 0.00795301 4 7.61386e-05 3.99849 +EDGE_SE3:QUAT 447 1088 -3.06554 -1.72121 -0.0819856 -7.74713e-05 -0.0126494 0.281632 0.959439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00197 0.000927905 -0.0891846 3.99974 -0.0119673 3.68471 +EDGE_SE3:QUAT 448 1088 -5.86515 -4.12096 -0.11715 -0.00030378 -0.0147299 0.523637 0.851814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00108 0.00143508 -0.0713032 4.00051 -0.0133966 2.90429 +EDGE_SE3:QUAT 1089 1090 4.20239 -0.328984 0.00960138 0.000179818 -0.000342203 -0.0399362 0.999202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.41522e-07 -0.002645 4 5.21988e-05 3.99362 +EDGE_SE3:QUAT 396 1089 5.60501 1.72245 0.0282528 0.00351942 0.00331303 -0.999162 0.0406362 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 3.69155e-05 0.0141143 4.00018 0.012056 0.0066915 +EDGE_SE3:QUAT 397 1089 1.39714 1.7731 0.0126018 0.000545915 0.00606841 -0.999282 0.0373816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.36314e-05 0.00219095 3.99987 0.0240255 0.00573525 +EDGE_SE3:QUAT 398 1089 -2.74621 1.88055 -0.0744064 0.0148116 0.00487255 -0.999296 0.0341309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99909 0.000111149 0.059345 4.00352 0.0154115 0.00560078 +EDGE_SE3:QUAT 399 1089 -6.82459 1.89105 -0.0398589 0.0113389 0.00499756 -0.999028 0.0422976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99945 9.88263e-05 0.0454773 4.00206 0.0160818 0.00773916 +EDGE_SE3:QUAT 446 1089 4.5979 -1.62826 -0.0463891 0.00576192 0.0100786 -0.125537 0.992021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00177 -9.13993e-05 0.0873535 3.99953 -0.00561473 3.93887 +EDGE_SE3:QUAT 447 1089 0.776785 -0.159649 2.2453e-05 0.00345976 -0.00317009 0.139552 0.990204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -1.02123e-05 -0.0303433 3.99994 -0.00223363 3.92233 +EDGE_SE3:QUAT 448 1089 -3.34227 -0.822391 -0.0326321 0.000912933 -0.0053452 0.394715 0.918788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.00021769 -0.0370458 3.99999 -0.00685729 3.37714 +EDGE_SE3:QUAT 1090 1091 4.01151 -0.0907592 0.0153248 -0.000597843 -0.00059292 0.00136985 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.4255e-06 -0.00473352 4 -3.24491e-06 4 +EDGE_SE3:QUAT 395 1090 5.61935 1.66098 0.0292263 0.00404663 0.00181731 -0.99998 0.00454356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.77471e-05 0.016187 4.00025 0.00712241 0.000160764 +EDGE_SE3:QUAT 396 1090 1.4012 1.7055 0.00771806 0.00297995 0.00309034 -0.999991 0.00071553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.6742e-05 0.0119199 4.0001 0.0123448 7.56665e-05 +EDGE_SE3:QUAT 397 1090 -2.81793 1.78794 0.0177078 -4.27049e-05 -0.00571417 0.999979 0.00298613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.9605e-07 0.000170825 3.99987 0.0228568 0.000166289 +EDGE_SE3:QUAT 398 1090 -6.94527 1.92921 -0.192054 -0.0142741 -0.00517247 0.999869 0.00569077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99919 0.000322632 0.0570962 4.00313 0.0213617 0.00105867 +EDGE_SE3:QUAT 447 1090 4.88527 0.685989 0.0398844 0.00387468 -0.00319785 0.0998059 0.994994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -2.91525e-05 -0.0298122 3.99994 -0.00155747 3.96038 +EDGE_SE3:QUAT 448 1090 -0.223622 1.98647 0.029832 0.00167639 -0.00543118 0.357352 0.933953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 0.000220892 -0.0419791 3.99996 -0.00738224 3.48964 +EDGE_SE3:QUAT 449 1090 -5.29209 0.692214 0.00231794 0.00272968 -0.00515083 0.565174 0.824951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000317568 -0.037709 4.00009 -0.0099628 2.72265 +EDGE_SE3:QUAT 790 1090 1.0822 6.76285 0.149989 0.00791609 0.0053224 -0.485947 0.873936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00088 -0.000503928 0.0673379 3.99991 -0.018533 3.05655 +EDGE_SE3:QUAT 1091 1092 4.08371 -0.0848911 0.0108499 0.00112504 -0.00261675 0.00256323 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -1.13804e-05 -0.0209689 3.99997 -2.67053e-05 4.00008 +EDGE_SE3:QUAT 394 1091 5.86526 1.64972 0.0505201 0.00573226 0.00434996 -0.999913 0.0110956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 9.25169e-05 0.0229335 4.00046 0.0168887 0.000695258 +EDGE_SE3:QUAT 395 1091 1.59165 1.70704 0.0117358 0.00332078 0.00239482 -0.999975 0.00584417 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.05194e-05 0.0132839 4.00016 0.00942376 0.000202936 +EDGE_SE3:QUAT 396 1091 -2.60429 1.79573 0.000355711 0.00237733 0.00385514 -0.999988 0.00210049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.66239e-05 0.00950956 4.00003 0.0153808 9.93979e-05 +EDGE_SE3:QUAT 397 1091 -6.84326 1.90343 0.0332484 0.000729993 -0.00651927 0.999977 0.00159112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.95545e-05 -0.00292017 3.99984 0.0260671 0.00018214 +EDGE_SE3:QUAT 448 1091 2.83858 4.60612 0.0920251 0.00131387 -0.00634767 0.358498 0.933508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 0.000292396 -0.0464866 3.99996 -0.00802733 3.48645 +EDGE_SE3:QUAT 449 1091 -3.75311 4.38923 0.0678432 0.00264643 -0.00616438 0.566252 0.824205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 0.000413287 -0.0417557 4.00013 -0.0106081 2.71784 +EDGE_SE3:QUAT 790 1091 3.11658 3.30922 0.0925983 0.00692553 0.00504389 -0.484628 0.874678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 -0.000429982 0.0609888 3.99993 -0.0165699 3.06147 +EDGE_SE3:QUAT 791 1091 -2.80313 3.3745 0.0908719 0.00497537 0.00640947 -0.270192 0.962772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 -0.00020559 0.0611235 3.99981 -0.00871314 3.70892 +EDGE_SE3:QUAT 1092 1093 4.05577 -0.073412 0.0158212 -0.00038164 0.00351124 0.00284885 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -4.52068e-06 0.0281038 3.99995 3.99301e-05 4.00016 +EDGE_SE3:QUAT 393 1092 5.99019 1.57384 0.0178527 0.00156391 0.00406672 -0.999816 0.0186617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.66689e-05 0.00625927 3.99998 0.0160194 0.00146701 +EDGE_SE3:QUAT 394 1092 1.79079 1.65037 0.00810308 0.00316644 0.00333662 -0.999897 0.0135613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.00863e-05 0.0126695 4.00012 0.0129975 0.000818017 +EDGE_SE3:QUAT 395 1092 -2.44984 1.73874 -0.00131817 0.000711589 0.00135324 -0.999961 0.00865218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.86877e-06 0.00284669 4 0.00536269 0.000308657 +EDGE_SE3:QUAT 396 1092 -6.69404 1.86943 -0.00587626 -0.000456636 0.00305563 -0.999986 0.00427994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.28127e-06 -0.00182662 3.99997 0.0122375 0.000111546 +EDGE_SE3:QUAT 790 1092 5.19889 -0.195502 0.036638 0.00663955 0.00231739 -0.482508 0.875863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -0.000141644 0.0449393 3.99991 -0.0132211 3.06925 +EDGE_SE3:QUAT 791 1092 0.66532 1.14897 0.0344886 0.00472534 0.00360079 -0.26783 0.963448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -4.41864e-05 0.040227 3.9999 -0.00591579 3.71347 +EDGE_SE3:QUAT 792 1092 -4.06601 0.237449 -0.032584 0.00598731 -0.00366057 -0.00705676 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -8.78533e-05 -0.0287751 3.99995 0.000102816 4.00001 +EDGE_SE3:QUAT 1093 1094 4.11887 -0.077797 0.0209957 -0.000939877 -0.00237045 0.00311322 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 9.30887e-06 -0.0189286 3.99998 -2.95741e-05 4.00005 +EDGE_SE3:QUAT 392 1093 6.16589 1.43207 0.039338 0.00541633 0.00482312 -0.999692 0.0237344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 9.1305e-05 0.0216844 4.00041 0.0182403 0.00245413 +EDGE_SE3:QUAT 393 1093 1.94117 1.50626 0.0161708 0.005268 0.0047136 -0.999736 0.0218587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.79324e-05 0.0210878 4.00038 0.0179137 0.0021027 +EDGE_SE3:QUAT 394 1093 -2.27467 1.60768 -0.00174472 0.00672538 0.00377547 -0.999837 0.016345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 8.53192e-05 0.0269122 4.00069 0.0142161 0.00130028 +EDGE_SE3:QUAT 395 1093 -6.49676 1.75987 0.00400629 0.00436882 0.00187739 -0.999919 0.0118439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 2.76523e-05 0.0174789 4.0003 0.00709377 0.000650086 +EDGE_SE3:QUAT 791 1093 4.09784 -1.00414 0.0158946 0.00549483 0.00721172 -0.265053 0.964191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00105 -0.00025186 0.0683979 3.99975 -0.00954899 3.72016 +EDGE_SE3:QUAT 792 1093 -0.0170639 0.0973809 0.0120997 0.00563383 -0.000134094 -0.00402789 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -1.99994e-06 -0.000800376 4 1.43062e-06 3.99994 +EDGE_SE3:QUAT 793 1093 -3.97498 -0.973505 -0.0209104 0.000575289 -0.00196855 0.260967 0.965345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 2.08874e-05 -0.0158873 3.99999 -0.00207765 3.72765 +EDGE_SE3:QUAT 1094 1095 4.40634 -0.0867326 0.0185724 0.000470803 0.000806955 0.0035779 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.56894e-06 0.00643531 4 1.15077e-05 3.99996 +EDGE_SE3:QUAT 391 1094 6.25307 1.21958 0.0334673 0.00447909 0.00418488 -0.999599 0.0276559 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.46445e-05 0.0179378 4.00028 0.015719 0.00320172 +EDGE_SE3:QUAT 392 1094 2.04732 1.31737 0.0133066 0.00301087 0.0056904 -0.999611 0.0271402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.88415e-05 0.0120582 4.00004 0.0220673 0.00310457 +EDGE_SE3:QUAT 393 1094 -2.20699 1.39932 -0.00899668 0.00286528 0.00551307 -0.999688 0.0241898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.37047e-05 0.0114722 4.00003 0.0214666 0.00248878 +EDGE_SE3:QUAT 394 1094 -6.38171 1.56344 -0.0395562 0.00449191 0.0045247 -0.999791 0.019445 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 7.45968e-05 0.0179784 4.00026 0.017385 0.00166886 +EDGE_SE3:QUAT 792 1094 4.11447 -0.0155583 0.0384141 0.00497203 -0.00263393 -0.0011816 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.23483e-05 -0.0210006 3.99997 1.32176e-05 4.0001 +EDGE_SE3:QUAT 793 1094 -0.366821 1.0433 0.0152911 0.000509573 -0.00463182 0.263606 0.964619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 0.000118751 -0.0347997 3.99995 -0.00447949 3.72235 +EDGE_SE3:QUAT 794 1094 -4.98174 -0.457191 0.0231943 0.00243171 -0.00327001 0.517209 0.855849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 0.000142466 -0.0288023 4.00002 -0.00760039 2.93018 +EDGE_SE3:QUAT 1095 1096 4.26434 -0.0956191 0.0252613 -0.000255038 -0.00216105 -0.00812501 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.29605e-06 -0.0173119 3.99998 7.03356e-05 3.99981 +EDGE_SE3:QUAT 338 1095 1.24413 5.86126 0.151804 0.00995553 0.00678625 -0.425736 0.904767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00141 -0.000610268 0.0849695 3.99974 -0.0204308 3.2768 +EDGE_SE3:QUAT 339 1095 -5.18919 5.08073 0.0917498 0.00598524 0.00653922 -0.231724 0.972741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00089 -0.000134714 0.0642182 3.99976 -0.00790868 3.78625 +EDGE_SE3:QUAT 390 1095 6.12967 0.958869 0.0488339 0.00671092 0.00467624 -0.99949 0.030866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 9.57618e-05 0.026883 4.00068 0.017009 0.00406409 +EDGE_SE3:QUAT 391 1095 1.8701 1.06448 0.0176908 0.00538769 0.00363208 -0.999492 0.0312046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 5.86641e-05 0.021583 4.00044 0.0131514 0.00405478 +EDGE_SE3:QUAT 392 1095 -2.37314 1.16258 0.00502958 0.00394215 0.00514481 -0.999523 0.0302017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 7.50827e-05 0.0157917 4.00017 0.0195823 0.00380692 +EDGE_SE3:QUAT 393 1095 -6.61074 1.28255 -0.0141308 0.00372064 0.00491079 -0.999593 0.0278507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 6.83058e-05 0.0149011 4.00015 0.0187781 0.00324643 +EDGE_SE3:QUAT 793 1095 3.48444 3.21749 0.0789924 0.000773214 -0.00381114 0.266811 0.963741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 8.09364e-05 -0.0296516 3.99996 -0.00391326 3.71547 +EDGE_SE3:QUAT 794 1095 -2.85856 3.4153 0.0804746 0.00259012 -0.00235109 0.519841 0.854256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 9.21177e-05 -0.024973 4 -0.00703038 2.91922 +EDGE_SE3:QUAT 1096 1097 4.31549 -0.285742 0.0287451 0.000937185 0.000964811 -0.0671438 0.997742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.33174e-06 0.00841922 4 -0.000290492 3.98198 +EDGE_SE3:QUAT 338 1096 3.8648 2.53309 0.0875073 0.00880972 0.00495701 -0.432926 0.901373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00088 -0.000362911 0.0691138 3.99981 -0.0172731 3.25149 +EDGE_SE3:QUAT 339 1096 -1.41089 3.06034 0.0540213 0.00500088 0.00468053 -0.239453 0.970884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 -6.43633e-05 0.0480963 3.99986 -0.00619467 3.77123 +EDGE_SE3:QUAT 340 1096 -6.81057 0.951257 -0.212256 0.00205763 -0.0129983 0.0114481 0.999848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0027 -6.09519e-05 -0.10431 3.99932 -0.000590255 4.00219 +EDGE_SE3:QUAT 389 1096 6.10151 0.687428 0.0482192 0.00799135 0.00730871 -0.999697 0.0220914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000207586 0.0319904 4.00087 0.027797 0.00240131 +EDGE_SE3:QUAT 390 1096 1.8881 0.800936 0.0165479 0.00434696 0.00492 -0.999725 0.0225004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 7.90283e-05 0.0174018 4.00023 0.0188749 0.00218993 +EDGE_SE3:QUAT 391 1096 -2.39583 0.903362 0.000597846 0.00304706 0.00381504 -0.999726 0.0228808 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.36788e-05 0.0121983 4.0001 0.0146834 0.00218527 +EDGE_SE3:QUAT 392 1096 -6.61807 1.01121 0.00299707 0.00172245 0.0054018 -0.999737 0.022219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.05179e-05 0.00689567 3.99994 0.0212746 0.00209984 +EDGE_SE3:QUAT 794 1096 -0.80671 7.16608 0.142206 0.00351648 -0.00431988 0.51239 0.858735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 0.000257759 -0.0397269 4.00002 -0.0105494 2.95022 +EDGE_SE3:QUAT 1097 1098 4.23718 -0.637006 -0.0269186 -0.00439445 0.0120124 -0.158273 0.987313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00169 -0.000630575 0.0843302 3.99965 -0.00637786 3.90157 +EDGE_SE3:QUAT 338 1097 6.34915 -1.01741 0.0404712 0.00974248 0.00640196 -0.492619 0.870167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 -0.000759909 0.0820606 3.99987 -0.0229582 3.03099 +EDGE_SE3:QUAT 339 1097 2.2794 0.797005 0.0296079 0.00590055 0.00553308 -0.304007 0.952635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 -0.000180372 0.0584822 3.99982 -0.00963983 3.63117 +EDGE_SE3:QUAT 340 1097 -2.49657 0.758412 -0.0596224 0.00395431 -0.0116838 -0.0560092 0.998354 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00198 -0.000351517 -0.0904155 3.99951 0.00251893 3.98949 +EDGE_SE3:QUAT 341 1097 -6.64062 -1.81947 -0.107778 0.00635052 -0.0124991 0.220814 0.975215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00281 0.000617167 -0.109121 3.99936 -0.0123823 3.80794 +EDGE_SE3:QUAT 388 1097 5.93545 0.686666 -0.0463106 0.00878149 -0.00555467 0.998819 0.0474623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 -0.000112405 -0.0352483 4.00122 0.0187747 0.00941038 +EDGE_SE3:QUAT 389 1097 1.75901 0.786267 0.0103123 -0.00862106 -0.00723397 0.998914 0.0452199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000303126 0.0345873 4.00084 0.0319116 0.00873398 +EDGE_SE3:QUAT 390 1097 -2.458 0.884717 0.00948829 -0.00517941 -0.0044382 0.998972 0.044822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000110779 0.0207774 4.0003 0.0195196 0.00823961 +EDGE_SE3:QUAT 391 1097 -6.73062 0.984401 0.00734319 -0.0040055 -0.0032315 0.999006 0.0442881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.3488e-05 0.0160671 4.00019 0.0142801 0.00796147 +EDGE_SE3:QUAT 1098 1099 4.18854 -0.895168 0.000527577 -0.000407087 -0.0013459 -0.198064 0.980188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -6.91181e-06 -0.0110822 3.99999 0.00110788 3.84311 +EDGE_SE3:QUAT 339 1098 5.35921 -2.1736 -0.0573548 0.00455749 0.0191083 -0.451025 0.892295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00401 -0.00311675 0.130108 4.00029 -0.0271742 3.1904 +EDGE_SE3:QUAT 340 1098 1.63928 -0.346679 0.00388254 0.00190867 0.00119551 -0.213511 0.976938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.02426e-06 0.0136594 3.99999 -0.00160789 3.8177 +EDGE_SE3:QUAT 341 1098 -2.54407 -0.581453 -0.0138481 0.00148939 -0.000488818 0.0635394 0.997978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.47028e-06 -0.00501945 4 -0.000171228 3.98386 +EDGE_SE3:QUAT 342 1098 -5.85081 -2.6831 -0.00284772 0.00307358 0.00128609 0.308961 0.951069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.5806e-06 -0.00181903 4 -0.000946375 3.61817 +EDGE_SE3:QUAT 387 1098 5.96012 1.56878 0.0451685 -0.00797249 -0.00754398 0.976993 0.212988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000294606 0.0334077 4.00017 0.039782 0.182152 +EDGE_SE3:QUAT 388 1098 1.76776 1.71708 0.0150262 -0.00266835 -0.00758973 0.978672 0.205272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.58887e-05 0.0108015 3.99976 0.0314046 0.168832 +EDGE_SE3:QUAT 389 1098 -2.38184 1.80685 -0.0776674 -0.019784 -0.0123445 0.9789 0.203007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 0.00192469 0.0831103 4.00289 0.075273 0.168078 +EDGE_SE3:QUAT 390 1098 -6.60437 1.92169 -0.0503405 -0.0166842 -0.00902052 0.979033 0.202815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.00136979 0.0701568 4.00234 0.058444 0.166678 +EDGE_SE3:QUAT 1099 1100 3.93134 -0.753067 0.005113 -6.33283e-05 -0.0014507 -0.166808 0.985988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -7.78599e-06 -0.0112491 3.99999 0.000928012 3.88873 +EDGE_SE3:QUAT 340 1099 5.06839 -2.89982 -0.0149931 0.00090285 0.000273107 -0.402839 0.91527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.32567e-07 0.00556749 4 -0.00137004 3.35089 +EDGE_SE3:QUAT 341 1099 1.71078 -0.935398 -0.0127118 0.00119011 -0.00162317 -0.135416 0.990787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.23693e-05 -0.0107196 3.99999 0.000674061 3.92668 +EDGE_SE3:QUAT 342 1099 -1.94219 -0.958058 -0.00197768 0.00283918 0.000703425 0.114319 0.99344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.24099e-07 0.00165646 4 1.8362e-05 3.94772 +EDGE_SE3:QUAT 343 1099 -5.40539 -2.15292 0.0344347 -0.000911839 0.00352629 0.292728 0.956189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 7.60299e-05 0.0276844 3.99997 0.00401952 3.65743 +EDGE_SE3:QUAT 387 1099 2.5343 4.11593 0.0137321 -0.00521306 -0.00947783 0.915419 0.402357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000136349 0.020331 3.99959 0.0375294 0.648097 +EDGE_SE3:QUAT 388 1099 -1.70107 4.2122 0.0244821 6.43315e-05 -0.0087257 0.918533 0.395248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -8.0451e-05 -0.0046205 4.00002 0.0218727 0.625057 +EDGE_SE3:QUAT 389 1099 -5.84868 4.30578 -0.18426 -0.0156125 -0.0166219 0.919413 0.392633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 0.000243251 0.0671216 3.99875 0.0837547 0.619843 +EDGE_SE3:QUAT 1100 1101 4.16894 -0.677629 0.0103098 0.0082868 0.0139178 -0.123063 0.992267 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00338 -0.000141188 0.121028 3.99909 -0.00761816 3.94308 +EDGE_SE3:QUAT 341 1100 5.28338 -2.69208 -0.00356038 0.00109835 -0.00286763 -0.298704 0.954341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -4.40172e-05 -0.0162376 4 0.00206698 3.64317 +EDGE_SE3:QUAT 342 1100 2.04874 -0.77856 -0.0101057 0.00227361 -0.000444419 -0.0529673 0.998594 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.94776e-06 -0.00209795 4 4.26766e-05 3.98878 +EDGE_SE3:QUAT 343 1100 -1.7376 -0.572893 0.0187844 -0.00109846 0.00201483 0.129146 0.991623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 4.51584e-06 0.0174007 3.99998 0.00115139 3.93336 +EDGE_SE3:QUAT 344 1100 -5.91918 -1.049 -0.208554 -0.00701315 -0.0194453 0.21172 0.977112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00386 0.00187383 -0.128015 3.99935 -0.0126347 3.82475 +EDGE_SE3:QUAT 1101 1102 4.1135 -0.321283 -0.00574152 -0.00142041 0.00091023 -0.0494374 0.998776 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.15933e-06 0.00641387 4 -0.000151404 3.99023 +EDGE_SE3:QUAT 342 1101 6.11584 -1.88965 0.00342018 0.0114458 0.0133113 -0.175748 0.984279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00339 -0.000227777 0.125334 3.99903 -0.011534 3.88037 +EDGE_SE3:QUAT 343 1101 2.46394 -0.174445 0.012304 0.00493424 0.0166616 0.00597919 0.999831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00432 0.000368638 0.133055 3.9989 0.000431353 4.00428 +EDGE_SE3:QUAT 344 1101 -1.86188 0.0683393 -0.0289893 0.000298277 -0.00486834 0.0894281 0.995981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 4.49957e-05 -0.038802 3.99991 -0.00173303 3.96839 +EDGE_SE3:QUAT 345 1101 -5.92363 0.00747032 -0.0768018 0.00237266 -0.00681224 0.111424 0.993747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00078 6.45628e-05 -0.0566422 3.9998 -0.00319436 3.95114 +EDGE_SE3:QUAT 1102 1103 4.45986 -0.187779 -0.0200992 -0.00281799 -0.00140154 -0.0218137 0.999757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.60335e-05 -0.0119417 3.99999 0.000132755 3.99813 +EDGE_SE3:QUAT 343 1102 6.56784 -0.42035 -0.131239 0.00268031 0.017637 -0.0436172 0.998889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00502 -0.000138321 0.142251 3.99874 -0.00309952 3.99744 +EDGE_SE3:QUAT 344 1102 2.24035 0.464786 0.00543003 -0.000903313 -0.00410185 0.0403181 0.999178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 3.04115e-05 -0.0323 3.99994 -0.000648132 3.99376 +EDGE_SE3:QUAT 345 1102 -1.85641 0.593557 -0.0275667 0.00131384 -0.00622238 0.0618865 0.998063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 2.55519e-05 -0.0504735 3.99984 -0.00156832 3.98532 +EDGE_SE3:QUAT 346 1102 -6.23816 0.718243 0.0637182 0.00266177 0.00285057 0.0608124 0.998142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 3.69532e-05 0.0207408 3.99998 0.00061017 3.98531 +EDGE_SE3:QUAT 1103 1104 3.9804 -0.151182 0.00148336 0.00250307 -0.00675499 -0.0101343 0.999923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0007 -7.81541e-05 -0.0537351 3.99982 0.0002746 4.00031 +EDGE_SE3:QUAT 344 1103 6.69548 0.654975 0.0232245 -0.00345101 -0.0055142 0.018247 0.999812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 8.73154e-05 -0.0433397 3.99988 -0.000395616 3.99914 +EDGE_SE3:QUAT 345 1103 2.57837 0.961207 0.00597087 -0.00122502 -0.00766251 0.0397986 0.999178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00091 9.20862e-05 -0.060582 3.99977 -0.00120312 3.99458 +EDGE_SE3:QUAT 346 1103 -1.79734 1.06943 0.0199437 -0.000272557 0.00142957 0.0387367 0.999248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.50647e-07 0.0115375 3.99999 0.000224105 3.99403 +EDGE_SE3:QUAT 347 1103 -6.03047 1.23963 0.0883477 -0.000767005 0.00980853 0.030032 0.999501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00154 3.94206e-05 0.078665 3.99961 0.0011815 3.99794 +EDGE_SE3:QUAT 1104 1105 4.09552 -0.106945 0.026541 0.000126324 0.00319546 -0.00361517 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 7.29038e-07 0.0255696 3.99996 -4.61961e-05 4.00011 +EDGE_SE3:QUAT 345 1104 6.5415 1.13767 0.0716848 0.00143147 -0.0141461 0.0297028 0.999458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00322 6.19909e-05 -0.113609 3.9992 -0.00168567 3.9997 +EDGE_SE3:QUAT 346 1104 2.16853 1.23532 0.0134515 0.00227314 -0.00529742 0.0284701 0.999578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -2.95861e-05 -0.0431081 3.99988 -0.000615697 3.99722 +EDGE_SE3:QUAT 347 1104 -2.06652 1.32318 0.0217385 0.00158086 0.00332169 0.0195642 0.999802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 2.56658e-05 0.0261881 3.99996 0.000255353 3.99864 +EDGE_SE3:QUAT 348 1104 -6.44171 1.51169 0.00549092 -0.000387079 0.00185101 0.01136 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.93985e-06 0.0148582 3.99999 8.44596e-05 3.99954 +EDGE_SE3:QUAT 1105 1106 3.992 -0.0966934 0.0308864 0.0023847 -0.00307685 -0.000311175 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -2.94095e-05 -0.0246065 3.99996 4.36992e-06 4.00015 +EDGE_SE3:QUAT 346 1105 6.25744 1.35101 0.088336 0.00216268 -0.00196764 0.0250511 0.999682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.54612e-05 -0.0163763 3.99998 -0.00020757 3.99756 +EDGE_SE3:QUAT 347 1105 2.03542 1.38641 0.0221389 0.0014912 0.00646653 0.0161128 0.999848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 5.43131e-05 0.0514311 3.99984 0.000415185 3.99962 +EDGE_SE3:QUAT 348 1105 -2.34202 1.48236 0.0247844 -0.000548403 0.00526289 0.00782773 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -6.35311e-06 0.0421549 3.99989 0.000164733 4.0002 +EDGE_SE3:QUAT 349 1105 -6.62064 1.59678 -0.0858433 0.000705595 -0.00290125 0.00530771 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -7.13463e-06 -0.0232546 3.99997 -6.16158e-05 4.00002 +EDGE_SE3:QUAT 1106 1107 4.4415 -0.107267 -0.01577 0.000223162 0.000480915 0.000109702 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.29855e-07 0.00384703 4 2.12248e-07 4 +EDGE_SE3:QUAT 347 1106 6.01501 1.39301 0.00146007 0.00417912 0.0034718 0.0153895 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 6.01256e-05 0.0269932 3.99996 0.000206882 3.99923 +EDGE_SE3:QUAT 348 1106 1.65561 1.45651 0.0171926 0.00202303 0.00216804 0.00767245 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.81428e-05 0.0171567 3.99998 6.58043e-05 3.99984 +EDGE_SE3:QUAT 349 1106 -2.63592 1.52785 -0.02983 0.00320066 -0.00601412 0.00480789 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00054 -7.32259e-05 -0.0483014 3.99985 -0.000113509 4.00049 +EDGE_SE3:QUAT 350 1106 -6.98922 1.67028 -0.165318 0.00151865 -0.0118975 0.00213774 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00226 -6.51825e-05 -0.0952653 3.99943 -9.68255e-05 4.00225 +EDGE_SE3:QUAT 1107 1108 4.13356 -0.0796988 -0.0169406 -0.000435865 0.00913815 -6.34919e-05 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00134 -1.60778e-05 0.0731262 3.99967 -3.19737e-06 4.00134 +EDGE_SE3:QUAT 348 1107 6.084 1.41175 -0.0198399 0.00229687 0.00282214 0.00795931 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 2.709e-05 0.022356 3.99997 8.9115e-05 3.99987 +EDGE_SE3:QUAT 349 1107 1.81335 1.47787 0.0119877 0.00330944 -0.00562975 0.00500829 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -7.1156e-05 -0.0452395 3.99987 -0.000110953 4.00041 +EDGE_SE3:QUAT 350 1107 -2.57074 1.57879 -0.0652134 0.00187723 -0.0115557 0.00224621 0.999929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00213 -7.97857e-05 -0.0925381 3.99947 -9.80693e-05 4.00212 +EDGE_SE3:QUAT 351 1107 -6.81462 1.70333 -0.0545443 0.00131813 -0.00794834 -0.000735518 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.001 -4.30498e-05 -0.063589 3.99975 2.53981e-05 4.00101 +EDGE_SE3:QUAT 1108 1109 4.09375 -0.0935124 0.0376417 -0.00231508 0.00554506 -0.000331831 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -5.16011e-05 0.0443556 3.99988 -9.06921e-06 4.00049 +EDGE_SE3:QUAT 349 1108 5.93793 1.4414 0.0454814 0.00273919 0.00360664 0.004871 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 4.07369e-05 0.028693 3.99995 7.0608e-05 4.00011 +EDGE_SE3:QUAT 350 1108 1.56147 1.51527 0.0180092 0.000893441 -0.00241706 0.00207369 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -8.36057e-06 -0.0193589 3.99998 -1.99556e-05 4.00008 +EDGE_SE3:QUAT 351 1108 -2.70055 1.60804 0.00395753 0.00062168 0.0012586 -0.000831361 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.10078e-06 0.010075 3.99999 -4.16526e-06 4.00002 +EDGE_SE3:QUAT 352 1108 -6.90925 1.71042 0.0289547 0.00491681 0.00165589 -0.0039271 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.30594e-05 0.0134782 3.99999 -2.62845e-05 3.99998 +EDGE_SE3:QUAT 1109 1110 4.47734 -0.0756258 0.0327578 -0.00214075 -0.00301529 0.00174937 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 2.61392e-05 -0.0240778 3.99996 -2.15151e-05 4.00013 +EDGE_SE3:QUAT 350 1109 5.62469 1.43755 0.0827257 -0.00168079 0.0032023 0.00162048 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -2.11695e-05 0.0256518 3.99996 2.03807e-05 4.00015 +EDGE_SE3:QUAT 351 1109 1.37987 1.51968 0.0328423 -0.00177323 0.0068988 -0.00103924 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 -5.01252e-05 0.0551771 3.99981 -3.07062e-05 4.00076 +EDGE_SE3:QUAT 352 1109 -2.82457 1.58554 0.0532243 0.00238688 0.00734417 -0.00382969 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 6.53705e-05 0.0588724 3.99978 -0.000109765 4.00081 +EDGE_SE3:QUAT 353 1109 -7.14188 1.73395 0.0164829 0.00594917 0.0041662 -0.00912488 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 9.78099e-05 0.0339772 3.99993 -0.000153476 3.99996 +EDGE_SE3:QUAT 1110 1111 4.07085 -0.0773819 0.0153034 -0.00268356 -0.00278888 0.00183773 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 3.01749e-05 -0.0222521 3.99997 -2.0929e-05 4.00011 +EDGE_SE3:QUAT 351 1110 5.85834 1.43316 0.00516689 -0.00406454 0.00394954 0.000850651 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -6.40174e-05 0.0316387 3.99994 1.19399e-05 4.00025 +EDGE_SE3:QUAT 352 1110 1.64178 1.48931 0.0212388 0.000221738 0.00431419 -0.00253633 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 2.69503e-06 0.0345222 3.99993 -4.36921e-05 4.00027 +EDGE_SE3:QUAT 353 1110 -2.67653 1.56826 0.007054 0.00397247 0.0010952 -0.00762817 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.81294e-05 0.00912431 3.99999 -3.51406e-05 3.99979 +EDGE_SE3:QUAT 354 1110 -7.15927 1.72533 0.0501054 0.00279599 0.00679723 -0.0133195 0.999884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 6.19178e-05 0.0548187 3.99981 -0.000363076 4.00004 +EDGE_SE3:QUAT 1111 1112 4.33604 -0.0872129 0.0272172 0.00150469 -0.00961721 0.00268226 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00147 -5.20437e-05 -0.07701 3.99963 -0.000100057 4.00145 +EDGE_SE3:QUAT 352 1111 5.68244 1.38418 0.00912841 -0.00273757 0.00165732 -0.00045562 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.81512e-05 0.0132435 3.99999 -3.1961e-06 4.00004 +EDGE_SE3:QUAT 353 1111 1.35854 1.44607 0.0115859 0.00127439 -0.00158049 -0.00571819 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -8.32123e-06 -0.012556 3.99999 3.58912e-05 3.99991 +EDGE_SE3:QUAT 354 1111 -3.13449 1.55106 0.0120713 0.000330191 0.00419709 -0.0110257 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 8.82829e-07 0.0336164 3.99993 -0.000185286 3.9998 +EDGE_SE3:QUAT 1112 1113 4.26686 -0.0785556 0.00489911 0.00211214 0.00767096 0.00250559 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 6.83046e-05 0.0613158 3.99977 7.98155e-05 4.00091 +EDGE_SE3:QUAT 353 1112 5.69004 1.29866 0.0543985 0.00280771 -0.0111309 -0.00290451 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00195 -0.000133666 -0.0889858 3.99951 0.000137689 4.00194 +EDGE_SE3:QUAT 354 1112 1.18087 1.35753 0.00498975 0.00161601 -0.00547674 -0.00803311 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -4.09949e-05 -0.0436583 3.99988 0.000176353 4.00022 +EDGE_SE3:QUAT 355 1112 -3.11073 1.47486 -0.0767612 -0.00220257 -0.00961167 -0.0139549 0.999854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00147 5.41249e-05 -0.0772644 3.99963 0.000535519 4.00071 +EDGE_SE3:QUAT 356 1112 -7.26728 1.57411 -0.00467515 -0.00317898 -0.00181142 -0.0145888 0.999887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.29861e-05 -0.0150432 3.99999 0.000110811 3.99921 +EDGE_SE3:QUAT 1113 1114 4.17024 -0.0744448 0.044555 9.66803e-05 -0.00355234 0.00049011 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -1.2256e-06 -0.0284205 3.99995 -6.93627e-06 4.0002 +EDGE_SE3:QUAT 354 1113 5.44316 1.21472 0.0602274 0.00365012 0.00219502 -0.00585172 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.19792e-05 0.0178155 3.99998 -5.19455e-05 3.99994 +EDGE_SE3:QUAT 355 1113 1.14263 1.28197 0.0148339 -0.000295026 -0.00198635 -0.0114115 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.26693e-06 -0.0159283 3.99998 9.09299e-05 3.99954 +EDGE_SE3:QUAT 356 1113 -3.0177 1.36504 0.0220328 -0.0010839 0.00593069 -0.0118619 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 -3.55687e-05 0.0472869 3.99986 -0.000281144 4 +EDGE_SE3:QUAT 357 1113 -7.16372 1.47554 0.0674773 -0.00242139 0.0101926 -0.0114255 0.99988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00163 -0.000126616 0.0812217 3.99959 -0.00046984 4.00113 +EDGE_SE3:QUAT 1114 1115 4.31368 -0.194002 0.0335904 0.00319299 -2.83531e-05 -0.0361365 0.999342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.57476e-06 0.00115701 4 -2.92461e-05 3.99478 +EDGE_SE3:QUAT 355 1114 5.29975 1.11326 0.0766567 -0.000161755 -0.00552128 -0.01093 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -4.42675e-06 -0.0441883 3.99988 0.000241472 4.00001 +EDGE_SE3:QUAT 356 1114 1.1407 1.18801 0.0201799 -0.00107761 0.00230356 -0.011479 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.12641e-05 0.0182767 3.99998 -0.00010475 3.99956 +EDGE_SE3:QUAT 357 1114 -3.00591 1.2945 0.0310112 -0.00247399 0.00647514 -0.0110035 0.999915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00064 -7.45233e-05 0.051472 3.99984 -0.000285157 4.00018 +EDGE_SE3:QUAT 358 1114 -6.97581 1.87072 -0.292542 -0.00639262 -0.0160953 -0.0522928 0.998482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00421 8.81409e-05 -0.13236 3.9989 0.00345923 3.99344 +EDGE_SE3:QUAT 1115 1116 4.33278 -0.393291 -0.0528492 -0.00724414 0.0118311 -0.100367 0.994854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 -0.000579441 0.0845781 3.99961 -0.00410032 3.96149 +EDGE_SE3:QUAT 356 1115 5.43844 0.89071 0.0369589 0.00185341 0.00212679 -0.047827 0.998852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.1323e-05 0.0180183 3.99998 -0.000438695 3.99093 +EDGE_SE3:QUAT 357 1115 1.30528 1.00215 0.0171428 0.000558775 0.00638599 -0.0472489 0.998863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 -3.21748e-05 0.0512406 3.99984 -0.00121165 3.99173 +EDGE_SE3:QUAT 358 1115 -2.72585 1.24032 -0.102621 -0.00286405 -0.0165162 -0.0884047 0.995944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00443 -0.000399214 -0.133737 3.99891 0.00593142 3.9732 +EDGE_SE3:QUAT 359 1115 -6.54661 2.83736 -0.077464 -0.00362766 -0.0114172 -0.233743 0.972225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00215 -0.000611955 -0.0938061 3.99957 0.0110597 3.78365 +EDGE_SE3:QUAT 1116 1117 4.16663 -0.770066 -0.00503879 -0.00114057 0.00216463 -0.183917 0.982939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.2498e-05 0.0139855 3.99999 -0.00118149 3.86475 +EDGE_SE3:QUAT 357 1116 5.56329 0.194528 -0.0933182 -0.00666114 0.0185996 -0.147338 0.988889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00419 -0.00145788 0.132475 3.9991 -0.00942729 3.91754 +EDGE_SE3:QUAT 358 1116 1.46216 0.0616577 -0.0144115 -0.00729334 -0.00405315 -0.187933 0.982146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 5.19319e-05 -0.0467868 3.99985 0.00485191 3.85927 +EDGE_SE3:QUAT 359 1116 -2.87711 0.518712 -0.0264443 -0.00642705 0.00129246 -0.329807 0.944026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 6.57609e-05 -0.0148923 3.99997 0.00394548 3.56495 +EDGE_SE3:QUAT 360 1116 -6.77936 2.6217 0.0255188 -0.00685693 0.00832321 -0.511258 0.859359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 -6.47912e-06 0.00752296 4.00004 0.00420168 2.95436 +EDGE_SE3:QUAT 1117 1118 4.17325 -0.91838 0.00225001 0.00226916 0.000246321 -0.202557 0.979268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.3852e-06 0.00721529 4 -0.000912549 3.83589 +EDGE_SE3:QUAT 358 1117 5.03118 -2.1667 0.045059 -0.0069272 -0.00330048 -0.364919 0.931008 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -8.95229e-05 -0.0489563 3.99986 0.0104036 3.46793 +EDGE_SE3:QUAT 359 1117 -0.128451 -2.68248 -0.0068106 -0.00707819 0.00226763 -0.497575 0.867389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 9.31498e-05 -0.0234478 3.99991 0.00988185 3.00979 +EDGE_SE3:QUAT 360 1117 -5.47409 -1.41067 0.00950939 -0.00806083 0.00910238 -0.660731 0.750525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 0.000257099 -0.0145196 3.99983 0.018085 2.25362 +EDGE_SE3:QUAT 1118 1119 4.31146 -0.918603 -0.00421855 0.00538616 0.0147439 -0.17107 0.985134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00371 -0.000637252 0.123757 3.99913 -0.0107454 3.88677 +EDGE_SE3:QUAT 359 1118 1.19892 -6.71569 0.0281223 -0.00498946 -0.000266209 -0.663133 0.748485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -9.10081e-05 -0.0289588 3.99999 0.0132236 2.24123 +EDGE_SE3:QUAT 1119 1120 4.2375 -0.483988 0.00121709 0.00032062 0.000201019 -0.0827578 0.99657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.16459e-07 0.00190861 4 -8.31386e-05 3.97261 +EDGE_SE3:QUAT 1120 1121 4.40538 -0.287417 0.0164961 0.00262812 -0.00021792 -0.0288076 0.999581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.07393e-07 -0.000833165 4 7.62926e-06 3.99668 +EDGE_SE3:QUAT 965 1120 -0.333727 -6.70851 0.0504253 -0.00618149 -0.00371721 0.867101 0.498081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 8.22698e-05 0.028406 3.99994 0.0250162 0.992748 +EDGE_SE3:QUAT 1121 1122 4.01309 -0.0909117 0.0181212 0.00309529 -0.00373037 0.000976836 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -4.59423e-05 -0.0298802 3.99994 -1.35662e-05 4.00022 +EDGE_SE3:QUAT 964 1121 3.1597 -2.72703 0.0381312 -0.00786241 -0.00471348 0.941161 0.337834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000277694 0.0349083 4.00018 0.0325228 0.457136 +EDGE_SE3:QUAT 965 1121 -2.31614 -2.76137 0.0421334 -0.00434486 -0.00151011 0.852193 0.523207 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 7.18117e-05 0.0211902 4.00002 0.0155373 1.09518 +EDGE_SE3:QUAT 966 1121 -7.15424 -1.35491 0.0838192 -0.00397629 0.00281537 0.770788 0.637073 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 0.000232916 0.0280365 4.00018 0.010408 1.62371 +EDGE_SE3:QUAT 1060 1121 4.12287 4.9932 0.140708 0.00883194 0.00791115 -0.527707 0.849344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00146 -0.00107447 0.0843695 4.00006 -0.0241268 2.88787 +EDGE_SE3:QUAT 1061 1121 -2.63344 5.35861 0.0791972 0.00230002 0.0072181 -0.324326 0.945915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 -0.000355961 0.0572118 3.99989 -0.00922933 3.58007 +EDGE_SE3:QUAT 1122 1123 4.00966 -0.0530646 0.0104778 -0.000985687 -0.00163138 0.00640193 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.78726e-06 -0.0129746 3.99999 -4.15131e-05 3.99988 +EDGE_SE3:QUAT 963 1122 4.3215 0.681258 0.0212146 -0.00469586 0.00207334 0.990632 0.136464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 3.79043e-05 0.0193426 4.00038 -0.0028789 0.0745876 +EDGE_SE3:QUAT 964 1122 0.141043 -0.110595 0.0132947 -0.00336277 -0.00285299 0.941593 0.336723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.84084e-05 0.0146667 3.99999 0.0163405 0.453659 +EDGE_SE3:QUAT 965 1122 -4.03321 0.847789 0.0430899 0.00035351 -0.000539789 0.852868 0.522126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.60243e-06 -0.0024782 4 -0.00023662 1.09046 +EDGE_SE3:QUAT 1060 1122 5.80819 1.34051 0.0713201 0.009808 0.00301908 -0.526849 0.849897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -0.000361257 0.0653794 3.99986 -0.0213419 2.89078 +EDGE_SE3:QUAT 1061 1122 0.467301 2.82077 0.0391737 0.00422163 0.00249066 -0.323432 0.946239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -3.47994e-05 0.0321259 3.99994 -0.00589064 3.58182 +EDGE_SE3:QUAT 1062 1122 -4.64254 2.16076 0.017783 0.00518217 0.00169856 -0.152205 0.988334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.16928e-05 0.0224379 3.99996 -0.0019347 3.90746 +EDGE_SE3:QUAT 1123 1124 4.07676 -0.0949487 0.00651155 0.00136494 0.00452848 -0.000682041 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 2.44057e-05 0.0362415 3.99992 -1.16908e-05 4.00033 +EDGE_SE3:QUAT 962 1123 3.94544 2.4795 -0.00840463 -0.0018827 0.0018478 -0.998371 0.0570018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.64808e-05 -0.00756473 4.00003 0.00818709 0.013028 +EDGE_SE3:QUAT 963 1123 0.505401 1.815 -0.00573616 -0.00341271 0.00111785 0.991497 0.130078 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.28362e-05 0.0140125 4.0002 -0.000792108 0.0677314 +EDGE_SE3:QUAT 964 1123 -2.89849 2.46716 0.00768037 -0.0022847 -0.00438894 0.94371 0.330736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.60671e-05 0.00924104 3.99991 0.0183267 0.437662 +EDGE_SE3:QUAT 965 1123 -5.78357 4.3885 0.0586582 0.00122708 -0.00218757 0.856041 0.516901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.43589e-05 -0.00886403 4.00006 -0.000230724 1.06877 +EDGE_SE3:QUAT 1061 1123 3.57844 0.335712 0.0178048 0.00292531 0.00129674 -0.3175 0.948253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -5.04879e-06 0.0192422 3.99998 -0.00355172 3.59687 +EDGE_SE3:QUAT 1062 1123 -0.852121 0.907662 0.00669893 0.00390589 0.000212096 -0.146021 0.989274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.81826e-05 0.00838955 3.99999 -0.000777644 3.91473 +EDGE_SE3:QUAT 1063 1123 -5.31939 0.399757 0.000235758 -7.42276e-05 -0.00142533 -0.0399069 0.999202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.52591e-06 -0.011411 3.99999 0.000227745 3.99366 +EDGE_SE3:QUAT 1124 1125 4.37812 -0.118688 0.0261177 0.00122731 -0.00166229 -0.00299959 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -8.32249e-06 -0.0132541 3.99999 1.99378e-05 4.00001 +EDGE_SE3:QUAT 960 1124 5.91195 4.5627 0.0108596 0.000721729 0.00415041 -0.870223 0.492639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.51502e-05 0.00770136 4.00008 0.0052807 0.970813 +EDGE_SE3:QUAT 961 1124 3.07906 2.70586 0.00800531 0.00534351 -0.00140668 -0.959219 0.282609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000157797 0.0235248 4.00026 -0.0156532 0.319682 +EDGE_SE3:QUAT 962 1124 -0.0884547 2.1139 0.00680353 0.00274247 0.000661829 -0.998402 0.0564325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.04033e-06 0.0110231 4.00012 0.00139213 0.0127695 +EDGE_SE3:QUAT 963 1124 -3.41683 2.95881 -0.0276473 -0.00777867 0.00294972 0.991336 0.131089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000108973 0.0319582 4.00103 -0.00327801 0.0689999 +EDGE_SE3:QUAT 1061 1124 6.7791 -2.2103 0.00199286 0.00531284 0.00539637 -0.318133 0.948016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 -0.000194029 0.0557089 3.99985 -0.00955498 3.59594 +EDGE_SE3:QUAT 1062 1124 3.03961 -0.360237 0.00284403 0.00582994 0.00464198 -0.146294 0.989213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 3.52886e-05 0.0460426 3.99986 -0.00358451 3.91492 +EDGE_SE3:QUAT 1063 1124 -1.2468 -0.0246807 0.0125822 0.00127211 0.00316045 -0.0406452 0.999168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 6.46746e-06 0.0258416 3.99996 -0.000528688 3.99356 +EDGE_SE3:QUAT 1064 1124 -5.37291 -0.0684427 -0.00305825 0.00234159 0.00311756 -0.0131825 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 2.66265e-05 0.025305 3.99996 -0.000167049 3.99946 +EDGE_SE3:QUAT 1125 1126 4.29499 -0.107145 0.0270262 0.00031072 -0.00290145 -0.00146725 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -3.90177e-06 -0.0232067 3.99997 1.7088e-05 4.00013 +EDGE_SE3:QUAT 960 1125 3.57463 0.892114 0.0183983 5.45719e-05 0.00220235 -0.871505 0.490381 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.12918e-07 0.00235939 4.00001 0.0038224 0.961905 +EDGE_SE3:QUAT 961 1125 -0.65791 0.433695 -0.00137987 0.00441999 -0.00333754 -0.960006 0.279926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.72223e-05 0.0190484 4.00005 -0.0199312 0.313634 +EDGE_SE3:QUAT 962 1125 -4.44901 1.74354 0.0103955 0.00113122 -0.000653806 -0.998545 0.0539094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.28616e-06 0.00454373 4.00002 -0.00308271 0.0116324 +EDGE_SE3:QUAT 1062 1125 7.18589 -1.74771 -0.016932 0.00709196 0.00286185 -0.149472 0.988736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 7.87961e-05 0.0346636 3.99991 -0.00288559 3.91093 +EDGE_SE3:QUAT 1063 1125 3.08702 -0.498377 0.0118813 0.00264726 0.00156001 -0.043474 0.99905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.59072e-05 0.0138241 3.99999 -0.000310069 3.99249 +EDGE_SE3:QUAT 1064 1125 -0.990501 -0.303661 -0.000640347 0.00361552 0.00161324 -0.0164012 0.999858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.392e-05 0.0136121 3.99999 -0.000113315 3.99897 +EDGE_SE3:QUAT 1065 1125 -5.08612 -0.210664 -0.0133356 0.00210782 0.00237449 -0.0168247 0.999853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 1.82525e-05 0.0194136 3.99998 -0.000164199 3.99896 +EDGE_SE3:QUAT 1126 1127 4.2599 -0.0932339 0.0143332 -0.00138401 -0.00251896 0.000876566 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.40662e-05 -0.0201375 3.99997 -9.03491e-06 4.0001 +EDGE_SE3:QUAT 959 1126 6.24602 -1.54638 0.0752669 0.00462645 -0.00490086 -0.77252 0.634954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.42039e-05 0.015787 3.99988 -0.0169577 1.61288 +EDGE_SE3:QUAT 960 1126 1.24099 -2.72526 0.0358515 -0.00236506 0.000507166 -0.872208 0.48913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.97905e-05 -0.0117249 4.00002 0.0079633 0.957048 +EDGE_SE3:QUAT 961 1126 -4.34228 -1.78556 -0.00319321 0.0014928 -0.00446235 -0.960528 0.278145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.03607e-05 0.00585479 3.99992 -0.0175567 0.309551 +EDGE_SE3:QUAT 1063 1126 7.37668 -0.977787 0.0246621 0.00269529 -0.0013816 -0.0452718 0.99897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.38672e-05 -0.0095565 3.99999 0.000205117 3.99182 +EDGE_SE3:QUAT 1064 1126 3.30819 -0.55343 0.00576258 0.00365132 -0.00126409 -0.0179419 0.999832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.7144e-05 -0.00932174 3.99999 8.13834e-05 3.99873 +EDGE_SE3:QUAT 1065 1126 -0.784896 -0.453793 -0.00886937 0.00260193 -0.000501311 -0.018417 0.999827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.30422e-06 -0.00343351 4 2.98584e-05 3.99865 +EDGE_SE3:QUAT 1066 1126 -5.10693 -0.425686 -0.0220469 0.00298083 0.00128197 -0.013817 0.999899 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.56752e-05 0.0107469 3.99999 -7.52509e-05 3.99927 +EDGE_SE3:QUAT 1127 1128 4.24016 -0.0627933 0.010865 0.00139241 0.012333 0.00710555 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00242 9.46251e-05 0.0985895 3.99939 0.000355752 4.00223 +EDGE_SE3:QUAT 960 1127 -1.0531 -6.29294 0.0719362 -0.00503396 0.000208572 -0.871692 0.490029 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -0.000168553 -0.0257874 4.00015 0.0153748 0.960763 +EDGE_SE3:QUAT 1065 1127 3.45517 -0.703609 0.00824907 0.00110152 -0.00289495 -0.0175029 0.999842 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.60433e-05 -0.0229183 3.99997 0.000200097 3.99891 +EDGE_SE3:QUAT 1066 1127 -0.865585 -0.636192 -0.0119949 0.00177416 -0.00103902 -0.0126304 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.36414e-06 -0.00804131 4 5.02565e-05 3.99938 +EDGE_SE3:QUAT 1067 1127 -4.718 -1.2139 -0.140478 0.0040218 -0.0129723 0.0799974 0.996703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00278 0.000121554 -0.106693 3.99929 -0.00429654 3.97725 +EDGE_SE3:QUAT 1128 1129 4.29925 -0.0491488 0.0168194 -0.00111164 -0.000250419 0.00935474 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.03358e-06 -0.00187831 4 -8.59207e-06 3.99965 +EDGE_SE3:QUAT 1066 1128 3.36922 -0.809763 0.00642704 0.00304215 0.0110517 -0.0055934 0.999919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00193 0.000118655 0.0886508 3.99951 -0.000239479 4.00184 +EDGE_SE3:QUAT 1067 1128 -0.498249 -0.60796 -0.00867184 0.00419119 -0.000615459 0.0870111 0.996198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.01097e-05 -0.00922181 3.99999 -0.000463739 3.96974 +EDGE_SE3:QUAT 1068 1128 -4.23005 -1.72296 -0.0355247 0.00527851 -0.0011926 0.301401 0.953482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.40702e-05 -0.0262063 3.99995 -0.00483356 3.6368 +EDGE_SE3:QUAT 1129 1130 4.3181 -0.0527842 0.0240797 -0.000490281 5.68715e-06 0.00961176 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.96049e-08 0.000102037 4 5.80959e-07 3.99963 +EDGE_SE3:QUAT 1067 1129 3.73941 0.0744688 0.0161615 0.00300702 -0.000943473 0.0962961 0.995348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.43342e-05 -0.0108963 3.99999 -0.000578594 3.96294 +EDGE_SE3:QUAT 1068 1129 -0.673536 0.714786 0.00947369 0.0043903 -0.00175385 0.310232 0.950649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 3.06919e-06 -0.0273511 3.99995 -0.00497047 3.61521 +EDGE_SE3:QUAT 1069 1129 -4.91562 -0.496582 -0.00157156 0.00564857 -0.00128866 0.510496 0.85986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 7.6816e-05 -0.0351478 3.99994 -0.0113859 2.95788 +EDGE_SE3:QUAT 1130 1131 4.28122 -0.0459567 0.0366535 -0.00136299 -0.00359227 0.00389313 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 2.07316e-05 -0.028675 3.99995 -5.62042e-05 4.00014 +EDGE_SE3:QUAT 426 1130 4.57335 -3.2972 0.0357135 -0.00783558 -0.00161345 0.956657 0.291108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000348063 0.0347517 4.00059 0.0218355 0.339418 +EDGE_SE3:QUAT 427 1130 -1.21645 -3.85839 0.0462859 -0.00183945 0.0050332 0.876696 0.481016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.56539e-05 0.0139167 4.00019 -0.00404195 0.925583 +EDGE_SE3:QUAT 428 1130 -6.53389 -2.72477 0.0658807 0.00145137 0.00486401 0.802327 0.596863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.41469e-05 0.000297201 4 -0.00894935 1.42504 +EDGE_SE3:QUAT 1068 1130 2.85194 3.21683 0.0648695 0.00418706 -0.00193327 0.319495 0.947577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.34381e-05 -0.0281211 3.99995 -0.00520581 3.59189 +EDGE_SE3:QUAT 1069 1130 -2.7912 3.27143 0.0647828 0.00581902 -0.00131961 0.518766 0.854895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 8.70155e-05 -0.0363243 3.99994 -0.0119746 2.92385 +EDGE_SE3:QUAT 1131 1132 4.31826 -0.240689 0.0203974 -0.00384615 0.000745146 -0.0607591 0.998145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.52191e-06 0.00313072 4 -6.63967e-05 3.98524 +EDGE_SE3:QUAT 425 1131 5.53859 0.711541 0.0188534 -0.00571611 -7.94511e-05 0.999307 0.0367858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 3.05557e-05 0.0229104 4.00052 0.00199707 0.00554517 +EDGE_SE3:QUAT 426 1131 1.05362 -0.871391 0.00968625 -0.00500868 -0.0036306 0.957823 0.287291 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000112624 0.0216705 4.00007 0.0221765 0.330397 +EDGE_SE3:QUAT 427 1131 -3.45894 -0.233529 0.044942 0.00045369 0.00227839 0.878531 0.477679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.595e-06 -0.000335218 4 -0.00569087 0.912724 +EDGE_SE3:QUAT 1069 1131 -0.771835 7.03442 0.136349 0.00660214 -0.00505487 0.522271 0.852739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 0.000478178 -0.0589441 4 -0.017089 2.9098 +EDGE_SE3:QUAT 1132 1133 4.28328 -0.685207 0.0002188 0.00113271 0.00364256 -0.162033 0.986778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -3.79118e-05 0.0301659 3.99995 -0.00247176 3.89521 +EDGE_SE3:QUAT 424 1132 4.80923 2.60533 0.00963049 0.00254764 0.00376601 -0.988503 0.151134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.75164e-05 0.0106376 4.00012 0.0112013 0.0914271 +EDGE_SE3:QUAT 425 1132 1.23234 1.27527 -0.0104191 -0.00673016 -0.00443882 0.995171 0.0978246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000191162 0.0272725 4.00049 0.0225532 0.0385942 +EDGE_SE3:QUAT 426 1132 -2.43392 1.71669 0.00371227 -0.00658512 -0.00752535 0.93857 0.344944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 7.23398e-05 0.028139 3.99978 0.0375389 0.476544 +EDGE_SE3:QUAT 427 1132 -5.59418 3.53036 0.0640833 -0.00223359 -0.000636895 0.847874 0.530192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.11243e-05 0.0110748 4.00001 0.00775641 1.12447 +EDGE_SE3:QUAT 1133 1134 4.11219 -0.912121 0.00914181 -0.00405845 -0.00123032 -0.214521 0.97671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.1327e-05 -0.0192981 3.99997 0.00241754 3.81601 +EDGE_SE3:QUAT 423 1133 3.86379 2.60851 0.021161 0.00310546 0.0105922 -0.984987 0.172275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000167508 0.0133968 4.00005 0.0351083 0.119083 +EDGE_SE3:QUAT 424 1133 0.516469 1.97895 -0.0204673 -0.00585362 -0.00372148 0.99991 0.0114938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 9.51689e-05 0.0234193 4.00048 0.015422 0.000725021 +EDGE_SE3:QUAT 425 1133 -2.80349 2.78596 -0.0532235 -0.0097095 -0.00354464 0.965984 0.258396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000496716 0.0420465 4.00082 0.0306105 0.267779 +EDGE_SE3:QUAT 426 1133 -5.21899 5.00479 -0.0203747 -0.00875038 -0.00626483 0.870037 0.492869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 0.000102954 0.0392548 3.99979 0.0373296 0.972527 +EDGE_SE3:QUAT 1134 1135 4.22477 -0.922836 0.000184678 -0.000304322 -0.000527318 -0.195685 0.980667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -8.31201e-07 -0.00467495 4 0.000472567 3.84683 +EDGE_SE3:QUAT 421 1134 6.48277 3.75706 0.0457175 0.00477881 0.00576459 -0.958666 0.284437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.00010518 0.022351 4.00055 0.00853553 0.323778 +EDGE_SE3:QUAT 422 1134 3.20443 2.46293 0.00519392 0.00146619 0.00891712 -0.990047 0.140448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000110611 0.00623425 3.99985 0.0323071 0.0791796 +EDGE_SE3:QUAT 423 1134 -0.273254 2.05187 0.00820763 0.00110038 -0.0148672 0.999031 0.0414053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000135068 -0.0044237 3.99918 0.0588449 0.00772986 +EDGE_SE3:QUAT 424 1134 -3.51133 2.94058 -0.049664 -0.00356125 -0.00879321 0.974575 0.223859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.60926e-05 0.0144863 3.99968 0.0369008 0.200862 +EDGE_SE3:QUAT 1135 1136 4.05914 -0.576037 -0.0241961 0.004698 0.0200465 -0.102814 0.994487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00661 -0.000641325 0.163831 3.99838 -0.00846722 3.96442 +EDGE_SE3:QUAT 420 1135 6.1951 2.7591 -0.0615381 -0.0149854 0.0128822 -0.984186 0.176033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 -0.0010959 -0.0621328 4.00122 0.0680752 0.126122 +EDGE_SE3:QUAT 421 1135 2.40778 2.23375 0.00296919 0.0029487 0.00691761 -0.995828 0.0909415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.57292e-05 0.0119824 4.00004 0.0249737 0.0332751 +EDGE_SE3:QUAT 422 1135 -1.11214 2.18791 0.00369069 0.000709134 -0.00944136 0.998364 0.0563955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.43823e-05 -0.00286429 3.99968 0.0371453 0.01307 +EDGE_SE3:QUAT 423 1135 -4.4127 3.33202 0.0529984 0.00425257 -0.0149171 0.971462 0.236688 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 -0.000264609 -0.0199615 4.00038 0.043887 0.224719 +EDGE_SE3:QUAT 1136 1137 4.4071 -0.290613 0.022352 0.0065331 0.000345737 -0.0319745 0.999467 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 1.96623e-05 0.00526641 4 -9.74763e-05 3.99592 +EDGE_SE3:QUAT 419 1136 6.42718 1.81916 0.0523442 0.00434697 0.0153558 -0.996514 0.0818826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000351734 0.0176352 3.99966 0.0575717 0.0277323 +EDGE_SE3:QUAT 420 1136 2.1952 1.8793 0.0319372 0.00427131 0.0101646 -0.997223 0.0736593 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000186181 0.0172582 4.00004 0.0376082 0.0221334 +EDGE_SE3:QUAT 421 1136 -1.6684 2.06411 -0.0426056 -0.0225375 -0.00427093 0.999656 0.0127101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99799 0.000540144 0.0901531 4.008 0.0194235 0.00277345 +EDGE_SE3:QUAT 422 1136 -5.07175 3.21694 -0.000105283 -0.0178589 -0.0033522 0.98707 0.159253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99911 0.00129707 0.0740039 4.00425 0.0348039 0.103152 +EDGE_SE3:QUAT 1137 1138 4.07137 -0.142063 0.0226816 0.00290362 -0.00758122 -0.0118041 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00087 -0.000103411 -0.0602369 3.99977 0.000358861 4.00035 +EDGE_SE3:QUAT 418 1137 6.08629 1.26271 0.0805347 0.0107263 0.00887758 -0.998874 0.0453596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.000272514 0.0430441 4.00173 0.0314633 0.00894215 +EDGE_SE3:QUAT 419 1137 2.05741 1.38394 0.0318938 0.00469145 0.00890794 -0.998689 0.0501871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.0001656 0.0188471 4.00014 0.0335324 0.0104459 +EDGE_SE3:QUAT 420 1137 -2.20625 1.52135 0.0224395 0.00477494 0.00332475 -0.999118 0.041579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 4.27355e-05 0.019151 4.00035 0.0116575 0.00704114 +EDGE_SE3:QUAT 421 1137 -6.07882 2.47672 -0.213658 -0.0226957 0.00191663 0.998729 0.0449698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99794 0.000384314 0.0910354 4.00828 0.000528518 0.0101663 +EDGE_SE3:QUAT 1138 1139 4.19338 -0.124381 -0.00732353 0.00250372 -0.000397657 -0.00627068 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.68932e-06 -0.00299264 4 9.19449e-06 3.99984 +EDGE_SE3:QUAT 417 1138 6.45308 0.842762 0.0555072 0.00411093 0.0112861 -0.99965 0.0235714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000198353 0.0164615 3.99982 0.0443089 0.00278133 +EDGE_SE3:QUAT 418 1138 2.02714 1.02935 0.0134614 0.00312282 0.00564573 -0.999419 0.0334727 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.99412e-05 0.0125144 4.00006 0.0216854 0.00463859 +EDGE_SE3:QUAT 419 1138 -1.99305 1.12904 0.015915 -0.00300453 0.00551738 -0.99926 0.0379408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -6.3804e-05 -0.0120422 3.99999 0.0229014 0.0059256 +EDGE_SE3:QUAT 420 1138 -6.23058 1.32971 0.00129374 -0.00292782 0.000449445 -0.999556 0.0296553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.12339e-05 -0.0117266 4.00013 0.00248795 0.0035537 +EDGE_SE3:QUAT 1139 1140 4.23812 -0.11972 0.0196043 0.00130369 0.000358588 -0.00438276 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.91543e-06 0.00293718 4 -6.48233e-06 3.99993 +EDGE_SE3:QUAT 416 1139 6.58139 0.663906 0.0290974 0.0038302 0.00526747 -0.999895 0.012981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.88075e-05 0.0153252 4.00014 0.0206648 0.000839525 +EDGE_SE3:QUAT 417 1139 2.27719 0.772684 0.0165396 0.00344755 0.00875131 -0.999805 0.017366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.00012578 0.0137983 3.99991 0.0345013 0.0015516 +EDGE_SE3:QUAT 418 1139 -2.12283 0.875505 -0.0204375 0.00269965 0.00329069 -0.999615 0.0274066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.26903e-05 0.0108114 4.00008 0.0125471 0.00307312 +EDGE_SE3:QUAT 419 1139 -6.12785 0.941919 0.0318676 -0.00312947 0.00321019 -0.99948 0.0319456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.44066e-05 -0.0125364 4.0001 0.0136076 0.00416774 +EDGE_SE3:QUAT 1140 1141 4.21829 -0.0813386 0.0317632 -0.00390118 -0.000697964 -0.000976954 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.09986e-05 -0.00562932 4 2.71104e-06 4 +EDGE_SE3:QUAT 415 1140 6.7478 0.550432 0.0225075 0.00491312 0.00323315 -0.999965 0.00588699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.06063e-05 0.0196536 4.00035 0.0127017 0.000275528 +EDGE_SE3:QUAT 416 1140 2.35002 0.654093 0.0161377 0.00398972 0.00411944 -0.999949 0.00832754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 6.36307e-05 0.0159608 4.00019 0.0162104 0.000406778 +EDGE_SE3:QUAT 417 1140 -1.94653 0.736702 0.00334306 0.00385106 0.0074245 -0.99988 0.0130246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000115177 0.0154094 4.00003 0.0292859 0.000952381 +EDGE_SE3:QUAT 418 1140 -6.34969 0.762129 -0.0241097 0.00309735 0.00208887 -0.999736 0.0226706 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.12451e-05 0.0123991 4.00014 0.00778371 0.00210943 +EDGE_SE3:QUAT 1141 1142 4.20294 -0.0931001 0.0292002 -0.00316397 -0.000767553 -0.000373225 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.73853e-06 -0.00615451 4 1.10449e-06 4.00001 +EDGE_SE3:QUAT 414 1141 6.88732 0.473982 -0.00317744 0.00220717 0.0049839 -0.999983 0.00219734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.41784e-05 0.00882905 3.99998 0.0198969 0.000137773 +EDGE_SE3:QUAT 415 1141 2.54644 0.577958 0.00878398 0.00412665 0.00744231 -0.999953 0.00454203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000122979 0.0165083 4.00006 0.0296198 0.000369981 +EDGE_SE3:QUAT 416 1141 -1.84324 0.677978 0.00877446 0.00338574 0.00847375 -0.999931 0.00739009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000116874 0.0135455 3.99991 0.0336912 0.000548117 +EDGE_SE3:QUAT 417 1141 -6.1602 0.70759 -0.00159757 0.00326843 0.0117479 -0.999862 0.0112851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.00016282 0.0130791 3.99964 0.0466815 0.00109708 +EDGE_SE3:QUAT 1142 1143 4.05585 -0.0941051 -0.00753405 0.000188912 -0.00174081 0.000216129 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.29983e-06 -0.0139271 3.99999 -1.49135e-06 4.00005 +EDGE_SE3:QUAT 413 1142 6.67483 0.445704 0.0572936 -0.00599473 -0.00667577 0.99996 0.000371293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000160331 0.0239801 4.0004 0.0267255 0.000322851 +EDGE_SE3:QUAT 414 1142 2.6756 0.542444 0.0055133 0.00140478 0.00821066 -0.999963 0.00207292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.71484e-05 0.00561973 3.99976 0.0328183 0.000294359 +EDGE_SE3:QUAT 415 1142 -1.66187 0.637106 0.000312465 0.00338074 0.0107622 -0.999927 0.00437787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000148338 0.0135256 3.99973 0.0429287 0.000583148 +EDGE_SE3:QUAT 416 1142 -6.04984 0.696647 0.0149389 0.0025534 0.0117144 -0.999906 0.00669658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000125842 0.0102164 3.99957 0.0467143 0.000751104 +EDGE_SE3:QUAT 1143 1144 4.55448 -0.098123 -0.0150798 -0.00120113 0.0036213 0.0011869 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -1.70415e-05 0.0289887 3.99995 1.68306e-05 4.0002 +EDGE_SE3:QUAT 412 1143 6.78953 0.424938 0.0333741 -0.00105896 -0.00494741 0.999984 0.00258611 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.05166e-05 0.00423602 3.99992 0.0198111 0.00012936 +EDGE_SE3:QUAT 413 1143 2.62007 0.53702 0.00240328 -0.00428571 -0.0063623 0.999971 1.90587e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000109089 0.0171437 4.00013 0.0254519 0.000235418 +EDGE_SE3:QUAT 414 1143 -1.35954 0.614593 -0.0151015 -0.000371431 0.00833275 -0.999963 0.0020633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.12384e-05 -0.00148588 3.99972 0.0333357 0.000295418 +EDGE_SE3:QUAT 415 1143 -5.68581 0.689011 -0.0220137 0.00174022 0.0107061 -0.99993 0.00469519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.84472e-05 0.00696232 3.99959 0.0427549 0.000557347 +EDGE_SE3:QUAT 1144 1145 4.4457 -0.102493 0.00427848 0.000466782 0.00749579 0.00129216 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0009 1.57469e-05 0.0599707 3.99978 3.93965e-05 4.00089 +EDGE_SE3:QUAT 411 1144 6.59779 0.426114 -0.018349 0.00269874 -0.00701645 0.99996 0.00485531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.67778e-05 -0.0107961 3.99992 0.0279598 0.000318879 +EDGE_SE3:QUAT 412 1144 2.24539 0.53508 0.0125963 -0.00460506 -0.00627383 0.999968 0.00157241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000115891 0.0184212 4.00018 0.0251555 0.000252913 +EDGE_SE3:QUAT 413 1144 -1.90961 0.624265 -0.046492 0.00784975 0.00760908 -0.99994 0.00084101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000238239 0.0314008 4.00076 0.0303929 0.000480207 +EDGE_SE3:QUAT 414 1144 -5.89167 0.695093 -0.0239898 0.00303735 0.00975906 -0.999942 0.00335608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000120353 0.0121513 3.99977 0.0389538 0.000461335 +EDGE_SE3:QUAT 1145 1146 4.36487 -0.0980002 0.0323801 0.00364401 0.00052408 0.00172223 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.46687e-06 0.00411723 4 3.54712e-06 3.99999 +EDGE_SE3:QUAT 410 1145 6.55761 0.403329 0.0246093 -0.00430721 -0.00711927 0.999916 0.00996548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000122877 0.0172326 4.00008 0.0288155 0.000679083 +EDGE_SE3:QUAT 411 1145 2.16144 0.554659 0.0159678 -0.00495634 -0.00657079 0.99996 0.0035237 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000131136 0.0198268 4.00021 0.026425 0.000322499 +EDGE_SE3:QUAT 412 1145 -2.17495 0.66749 -0.0257629 -0.0122346 -0.00596139 0.999907 0.000783208 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9994 0.000294922 0.0489376 4.00225 0.0239415 0.00074444 +EDGE_SE3:QUAT 413 1145 -6.32132 0.727099 -0.112984 0.0153828 0.00745923 -0.999852 0.00212043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99905 0.000449309 0.0615294 4.00358 0.0296134 0.00118362 +EDGE_SE3:QUAT 1146 1147 4.28294 -0.0918932 0.0281174 0.00037103 -0.00510933 0.00148746 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -6.65496e-06 -0.0408849 3.9999 -3.01846e-05 4.00041 +EDGE_SE3:QUAT 409 1146 6.63042 0.37197 0.0682188 -0.00951614 -0.00637884 0.999687 0.0222313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000282227 0.0380936 4.00122 0.0271881 0.00252469 +EDGE_SE3:QUAT 410 1146 2.20099 0.562685 0.0186485 -0.00486667 -0.00368235 0.999945 0.00848306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 7.55237e-05 0.019469 4.00032 0.0150588 0.000439307 +EDGE_SE3:QUAT 411 1146 -2.18867 0.687367 0.00632803 -0.00541729 -0.00317692 0.999978 0.00224403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 7.02619e-05 0.0216694 4.00043 0.0128068 0.000178534 +EDGE_SE3:QUAT 412 1146 -6.51099 0.757507 -0.0988901 0.012911 0.00255198 -0.999913 0.001154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 0.000127538 0.0516405 4.00264 0.0100979 0.00069759 +EDGE_SE3:QUAT 1147 1148 4.11684 -0.0829028 0.0101374 -0.00125092 -0.00608648 1.16112e-05 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00059 3.04808e-05 -0.0486979 3.99985 -1.3952e-06 4.00059 +EDGE_SE3:QUAT 408 1147 6.71997 0.545307 0.0797749 -0.0110354 -0.00289305 0.999616 0.0252472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.000198671 0.0441819 4.00187 0.0137907 0.0030856 +EDGE_SE3:QUAT 409 1147 2.36865 0.636909 0.021722 -0.00443287 -0.00617611 0.999755 0.0207773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000112237 0.0177435 4.00013 0.0254164 0.00196707 +EDGE_SE3:QUAT 410 1147 -2.03663 0.745729 0.00207238 0.000295395 -0.00354319 0.999968 0.00717236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.88818e-06 -0.00118171 3.99995 0.0141539 0.000256206 +EDGE_SE3:QUAT 411 1147 -6.41218 0.803223 -0.00693941 -0.000347523 -0.00268711 0.999996 0.000905396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.68556e-06 0.00139011 3.99997 0.0107509 3.26577e-05 +EDGE_SE3:QUAT 1148 1149 4.3184 -0.14505 -0.00874144 -0.00538538 0.00326878 -0.0284951 0.999574 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -7.02142e-05 0.0242775 3.99997 -0.00033826 3.9969 +EDGE_SE3:QUAT 407 1148 6.87823 1.21507 0.0187636 0.000797065 -8.39296e-05 -0.99982 0.0189651 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.53966e-07 0.00318997 4.00001 -0.000456306 0.0014413 +EDGE_SE3:QUAT 408 1148 2.61353 0.8221 0.00878927 -0.00500774 -0.00400723 0.999674 0.024698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 9.11945e-05 0.0200492 4.00031 0.0169955 0.00261277 +EDGE_SE3:QUAT 409 1148 -1.74494 0.893898 -0.000186424 0.00165352 -0.00772663 0.99976 0.0204282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.91589e-05 -0.00661938 3.99982 0.0306038 0.00191446 +EDGE_SE3:QUAT 410 1148 -6.13831 0.873878 0.0217793 0.00622062 -0.00487163 0.999943 0.00712624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.000115915 -0.0248847 4.00053 0.0191333 0.000449466 +EDGE_SE3:QUAT 1149 1150 4.22294 -0.429469 0.0135349 -0.00460435 0.0168626 -0.103648 0.99446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00395 -0.00093628 0.12715 3.99908 -0.00649991 3.96106 +EDGE_SE3:QUAT 406 1149 6.32301 2.2944 -0.0840668 -0.0110204 0.00220588 -0.993004 0.117544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000406023 -0.044958 4.00171 0.0187531 0.0558667 +EDGE_SE3:QUAT 407 1149 2.5565 1.17574 0.00575149 -0.00380519 -0.00550907 0.999933 0.00945516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.47338e-05 0.0152234 4.0001 0.0223205 0.0005401 +EDGE_SE3:QUAT 408 1149 -1.68846 1.17847 -0.0429223 -0.00803667 -0.00992657 0.998506 0.0531194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000345473 0.0322758 4.00044 0.0428427 0.0120078 +EDGE_SE3:QUAT 409 1149 -6.05356 1.21271 0.0092728 -0.00128491 -0.0132262 0.998714 0.048934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.51974e-07 0.00514612 3.9993 0.0530856 0.0102911 +EDGE_SE3:QUAT 1150 1151 4.11886 -0.765881 0.0125244 0.00352771 -0.00316084 -0.172822 0.984942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.81936e-05 -0.0169917 3.99999 0.00122484 3.8806 +EDGE_SE3:QUAT 405 1150 5.50763 2.81076 0.0528434 0.00711515 0.0107147 -0.984821 0.173093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000102391 0.0301535 4.00099 0.0301359 0.120319 +EDGE_SE3:QUAT 406 1150 2.12408 1.69861 0.0262811 0.00516098 0.00740936 -0.99986 0.0141039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000149692 0.0206515 4.00023 0.0290442 0.00111324 +EDGE_SE3:QUAT 407 1150 -1.64434 1.68614 -0.0109519 -0.0201643 -0.0104532 0.993308 0.113244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 0.00166289 0.0821026 4.00475 0.0586248 0.0538666 +EDGE_SE3:QUAT 408 1150 -5.83116 2.04319 -0.0778745 -0.0238612 -0.0141555 0.987253 0.156723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99885 0.00266353 0.0985432 4.00537 0.0825496 0.102451 +EDGE_SE3:QUAT 1151 1152 4.32593 -0.892921 0.0054401 0.000867897 -0.00156485 -0.189103 0.981956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.18694e-05 -0.00993086 4 0.000855266 3.85698 +EDGE_SE3:QUAT 404 1151 4.65271 2.93035 0.0552333 0.00574784 0.0108869 -0.986817 0.161368 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000162311 0.0242377 4.00057 0.0335204 0.104602 +EDGE_SE3:QUAT 405 1151 1.39263 2.12309 0.0109933 0.00273337 0.00763967 -0.999967 0.000707222 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.373e-05 0.0109344 3.99989 0.0305436 0.000265122 +EDGE_SE3:QUAT 406 1151 -2.00731 2.33125 0.00901203 -0.000862517 -0.00444587 0.98727 0.158987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.0311e-05 0.00343544 3.99992 0.0177388 0.101191 +EDGE_SE3:QUAT 407 1151 -5.47719 3.33804 -0.127146 -0.0146055 -0.0104338 0.958885 0.283227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000971495 0.0631543 4.00068 0.0640715 0.322997 +EDGE_SE3:QUAT 1152 1153 3.96649 -0.751589 -0.00557139 0.00281962 0.00160949 -0.158149 0.98741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.06246e-05 0.0176579 3.99998 -0.00152407 3.90003 +EDGE_SE3:QUAT 403 1152 3.85823 2.9374 -0.00138002 0.00147507 0.00892667 -0.990333 0.138418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000110552 0.00625772 3.99985 0.032406 0.0769168 +EDGE_SE3:QUAT 404 1152 0.297069 2.39631 0.0138716 -0.00214974 -0.0106345 0.99955 0.0279712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.81655e-05 0.00860843 3.99959 0.0429336 0.00360932 +EDGE_SE3:QUAT 405 1152 -2.899 2.97868 0.00648743 5.42721e-05 -0.00693154 0.982095 0.188261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -6.16619e-05 -0.000598689 3.99986 0.0252211 0.141934 +EDGE_SE3:QUAT 406 1152 -5.79965 4.51581 0.0162491 0.00148476 -0.00374313 0.939518 0.342476 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.80937e-06 -0.00809157 4.00009 0.00717657 0.469197 +EDGE_SE3:QUAT 1153 1154 4.04927 -0.565296 -0.0179269 0.00436713 0.00530958 -0.0997971 0.994984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 2.64049e-05 0.0470437 3.99986 -0.00242105 3.96071 +EDGE_SE3:QUAT 402 1153 3.43347 2.80266 0.00466216 -0.000121948 0.00967163 -0.993877 0.110067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.40432e-05 -0.000392733 3.99966 0.0376244 0.0488173 +EDGE_SE3:QUAT 403 1153 -0.162569 2.56644 -0.00994492 -0.00205083 -0.00649741 0.99978 0.019837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.82761e-05 0.00820825 3.99989 0.0262894 0.00176373 +EDGE_SE3:QUAT 404 1153 -3.62758 3.37777 0.0124154 -0.00190279 -0.00803531 0.982591 0.185599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.74959e-05 0.00758312 3.99973 0.0321336 0.13807 +EDGE_SE3:QUAT 1154 1155 4.16282 -0.243318 0.0220627 0.00159096 -0.000500196 -0.0300063 0.999548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.71208e-06 -0.00342363 4 4.84808e-05 3.9964 +EDGE_SE3:QUAT 401 1154 3.48294 2.40125 0.0228418 0.00544582 0.0040599 -0.998613 0.0522077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 5.44513e-05 0.0218767 4.00046 0.013863 0.0110708 +EDGE_SE3:QUAT 402 1154 -0.623616 2.46229 -0.0107714 0.00460869 0.00576026 -0.999918 0.0104925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000103464 0.0184385 4.00022 0.0226502 0.000653638 +EDGE_SE3:QUAT 403 1154 -4.18241 3.28618 -0.0338854 -0.00663519 -0.00207974 0.992813 0.119474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000161897 0.0270751 4.00058 0.0142783 0.0573333 +EDGE_SE3:QUAT 1155 1156 4.21962 -0.140991 0.0258316 0.000388066 -0.00394703 -0.0132817 0.999904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -1.10597e-05 -0.0315078 3.99994 0.000209262 3.99954 +EDGE_SE3:QUAT 400 1155 3.37982 2.09713 0.0137944 0.0048118 0.00166275 -0.999891 0.0138684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 2.45171e-05 0.0192526 4.00036 0.00611481 0.000871366 +EDGE_SE3:QUAT 401 1155 -0.69443 2.21174 -0.00140656 0.0048743 0.00295797 -0.999744 0.0219133 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 4.62934e-05 0.0195114 4.00036 0.010965 0.00204606 +EDGE_SE3:QUAT 402 1155 -4.79196 2.61325 -0.0243252 -0.00407184 -0.00422398 0.999787 0.0198075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.34322e-05 0.016297 4.00018 0.0175257 0.00171259 +EDGE_SE3:QUAT 444 1155 3.99994 5.72701 0.148886 0.0137689 0.00410034 -0.555827 0.831174 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00135 -0.000820439 0.0918101 3.99979 -0.0317762 2.76633 +EDGE_SE3:QUAT 445 1155 -2.36594 6.03013 0.0941486 0.0098957 0.00548309 -0.397768 0.917416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00105 -0.000348174 0.0761525 3.99972 -0.0174525 3.36857 +EDGE_SE3:QUAT 1086 1155 3.06869 6.70248 0.156718 0.0137247 0.00540693 -0.500337 0.865705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00158 -0.000797732 0.0967769 3.99968 -0.0292023 3.00099 +EDGE_SE3:QUAT 1087 1155 -3.41521 6.7141 0.124209 0.0114983 0.00615429 -0.345925 0.938172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00125 -0.000262773 0.0846187 3.99959 -0.0167967 3.52312 +EDGE_SE3:QUAT 1156 1157 4.12738 -0.0975793 0.0043553 -0.00586085 -0.00145697 -0.0049984 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 3.52602e-05 -0.0120064 3.99999 2.99863e-05 3.99994 +EDGE_SE3:QUAT 399 1156 3.39529 2.01457 0.0151874 -0.00234811 -0.000905643 0.999951 0.00960398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.70197e-06 0.00939372 4.00008 0.00380224 0.000394623 +EDGE_SE3:QUAT 400 1156 -0.864952 2.12689 -0.00105821 0.000904523 0.00135639 -0.999998 0.000617553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.90452e-06 0.0036181 4.00001 0.00542111 1.21453e-05 +EDGE_SE3:QUAT 401 1156 -4.91198 2.18323 -0.0188189 0.000921534 0.00260644 -0.999961 0.00835865 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.88073e-06 0.00368657 3.99999 0.0103623 0.000309712 +EDGE_SE3:QUAT 444 1156 5.48233 1.76099 0.0737657 0.0115966 0.000722685 -0.567066 0.823591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -0.000230625 0.06524 3.99977 -0.0251547 2.71479 +EDGE_SE3:QUAT 445 1156 0.403807 2.84937 0.0418874 0.00847404 0.00189745 -0.40971 0.912175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -3.39163e-05 0.0485278 3.99984 -0.0124439 3.32913 +EDGE_SE3:QUAT 446 1156 -5.16362 1.64795 -0.00201908 0.00859053 0.000975617 -0.176388 0.984283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000103302 0.0252489 3.99994 -0.00274873 3.8757 +EDGE_SE3:QUAT 1086 1156 5.0387 2.97196 0.0809896 0.0120035 0.00194923 -0.51171 0.859072 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 -0.000245852 0.0707476 3.99973 -0.0234997 2.95385 +EDGE_SE3:QUAT 1087 1156 -0.296367 3.84568 0.0640123 0.0102906 0.0026431 -0.358445 0.93349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 5.261e-06 0.0576829 3.99976 -0.0126849 3.48688 +EDGE_SE3:QUAT 1088 1156 -5.52535 2.88513 -0.0170461 0.00678535 -0.000579457 -0.195567 0.980667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 5.18967e-05 0.0111455 3.99998 -0.00161727 3.84704 +EDGE_SE3:QUAT 1157 1158 4.11182 -0.0793112 0.0153426 0.00202246 0.012029 0.00448371 0.999916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00229 0.000112911 0.096168 3.99942 0.000222854 4.00223 +EDGE_SE3:QUAT 398 1157 3.37825 2.08707 0.0130503 -0.0046988 -0.00687037 0.999716 0.022317 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000131531 0.0188099 4.00013 0.0282883 0.00228083 +EDGE_SE3:QUAT 399 1157 -0.740037 2.18808 0.00149086 -0.00109477 -0.00669225 0.999866 0.0148738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.43039e-05 0.00438064 3.99984 0.026884 0.00107045 +EDGE_SE3:QUAT 400 1157 -4.97495 2.20801 -0.00155007 0.000240609 -0.00722794 0.999963 0.00466817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.8976e-06 -0.000962563 3.99979 0.0289005 0.000296223 +EDGE_SE3:QUAT 444 1157 6.85309 -2.10793 0.0214833 0.00624872 0.00314267 -0.570988 0.820929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -0.000304969 0.0474265 4 -0.0158793 2.69645 +EDGE_SE3:QUAT 445 1157 3.06333 -0.306166 -0.00216368 0.00246561 0.00312853 -0.414479 0.91005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -0.00010196 0.0297245 3.99998 -0.00648898 3.31305 +EDGE_SE3:QUAT 446 1157 -1.29864 0.118865 -0.0141539 0.00242692 0.000711045 -0.181761 0.983339 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.61029e-06 0.0105857 3.99999 -0.00111348 3.86788 +EDGE_SE3:QUAT 447 1157 -5.19241 -1.64993 -0.148207 0.00360584 -0.0127986 0.083152 0.996448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0027 0.000149891 -0.104973 3.99932 -0.0043924 3.9751 +EDGE_SE3:QUAT 1086 1157 6.90914 -0.700961 0.020001 0.00644301 0.00390609 -0.516263 0.856397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 -0.000328297 0.0524609 3.99996 -0.0155339 2.93458 +EDGE_SE3:QUAT 1087 1157 2.71476 1.00863 0.0182994 0.0043483 0.00339262 -0.363295 0.931658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -0.000102027 0.039241 3.99993 -0.00790608 3.47245 +EDGE_SE3:QUAT 1088 1157 -1.75759 1.21619 -0.0123776 0.00085393 -0.000736771 -0.200816 0.979628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.42093e-06 -0.00353878 4 0.000274215 3.8387 +EDGE_SE3:QUAT 1089 1157 -6.12295 0.221279 -0.102985 -0.00159505 -0.00975331 -0.0568757 0.998332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00154 -6.88989e-05 -0.0787611 3.99962 0.00224509 3.98861 +EDGE_SE3:QUAT 1158 1159 4.13501 -0.0912331 0.0134116 0.00180169 -0.00285197 0.00169401 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.0268e-05 -0.0228528 3.99997 -1.90158e-05 4.00012 +EDGE_SE3:QUAT 397 1158 3.42219 2.27217 0.0171629 -0.00243429 -0.00523681 0.999866 0.0153181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.96215e-05 0.0097408 3.99998 0.0212335 0.00107504 +EDGE_SE3:QUAT 398 1158 -0.705218 2.36251 -0.0118419 -0.0166515 -0.00465993 0.999686 0.0181454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99892 0.000427592 0.066633 4.00428 0.0210732 0.00253853 +EDGE_SE3:QUAT 399 1158 -4.82338 2.41301 0.0114057 -0.0131964 -0.00481563 0.999845 0.0106199 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99931 0.000296779 0.0527924 4.00266 0.0203975 0.001252 +EDGE_SE3:QUAT 445 1158 5.70418 -3.46194 -0.0211009 0.0089038 0.01325 -0.410554 0.911696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00323 -0.00173271 0.119397 3.99971 -0.0254066 3.32933 +EDGE_SE3:QUAT 446 1158 2.5095 -1.44298 -0.00914215 0.00625085 0.0122369 -0.177225 0.984074 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00267 -0.000395685 0.106399 3.99934 -0.00967221 3.87719 +EDGE_SE3:QUAT 447 1158 -1.11625 -1.05074 -0.0177384 0.00431505 -0.000704053 0.0877213 0.996135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.22541e-05 -0.0100864 3.99999 -0.000507714 3.96924 +EDGE_SE3:QUAT 448 1158 -4.53806 -2.56421 -0.0506257 0.00152156 -0.00268403 0.345885 0.938272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 5.522e-05 -0.0235491 3.99998 -0.00419152 3.52159 +EDGE_SE3:QUAT 1087 1158 5.68319 -1.84027 -0.0102288 0.0104079 0.0140277 -0.358991 0.933178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00394 -0.0016354 0.132358 3.99937 -0.0249919 3.48888 +EDGE_SE3:QUAT 1088 1158 1.98238 -0.489652 0.00379758 0.0050329 0.0106814 -0.196173 0.980498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00202 -0.000378968 0.0921531 3.99952 -0.00925663 3.84819 +EDGE_SE3:QUAT 1089 1158 -2.08082 -0.335593 -0.00305303 0.000869993 0.00207254 -0.0522756 0.99863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.84875e-06 0.0170574 3.99998 -0.000449933 3.98914 +EDGE_SE3:QUAT 1090 1158 -6.2505 -0.523893 -0.0078734 0.000584359 0.00239122 -0.0122092 0.999922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 3.93471e-06 0.0192114 3.99998 -0.00011737 3.9995 +EDGE_SE3:QUAT 1159 1160 4.19532 -0.0849092 0.0102361 -0.000212607 0.000229481 0.00251955 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.92865e-07 0.00184226 4 2.32325e-06 3.99998 +EDGE_SE3:QUAT 396 1159 3.5075 2.41546 0.00854831 -0.00243867 -0.000793701 0.999946 0.0100491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.11388e-06 0.00975612 4.00009 0.00337015 0.000430578 +EDGE_SE3:QUAT 397 1159 -0.678848 2.48169 0.00836101 0.000521103 -0.00363713 0.999909 0.0130129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.85191e-06 -0.00208505 3.99995 0.0144881 0.000730919 +EDGE_SE3:QUAT 398 1159 -4.78539 2.60875 -0.132661 -0.0137848 -0.00293024 0.999766 0.0164206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99925 0.000235083 0.0551574 4.00297 0.0135379 0.00188525 +EDGE_SE3:QUAT 446 1159 6.3331 -2.95902 -0.104208 0.00755588 0.00908748 -0.175245 0.984454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 -0.000114749 0.0849716 3.99956 -0.00779768 3.87896 +EDGE_SE3:QUAT 447 1159 2.95584 -0.417988 0.00491159 0.00631145 -0.00344068 0.0892765 0.995981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -7.83284e-05 -0.0339232 3.99992 -0.00160767 3.96841 +EDGE_SE3:QUAT 448 1159 -1.3279 0.0512818 -0.0113838 0.00417742 -0.0049045 0.347333 0.93772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 0.000191412 -0.0483719 3.9999 -0.00895128 3.51802 +EDGE_SE3:QUAT 449 1159 -5.3943 -1.52474 -0.0302551 0.00490034 -0.00430937 0.556537 0.830797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 0.000346712 -0.0457457 4.00004 -0.0137416 2.76159 +EDGE_SE3:QUAT 1088 1159 5.75308 -2.15321 -0.0782369 0.0061442 0.00752529 -0.194632 0.980828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -0.00012025 0.0708202 3.9997 -0.00723711 3.84973 +EDGE_SE3:QUAT 1089 1159 2.02096 -0.857869 -0.00844758 0.00270229 -0.000833166 -0.0506292 0.998714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.55322e-06 -0.00500069 4 0.000112549 3.98975 +EDGE_SE3:QUAT 1090 1159 -2.12617 -0.711701 -0.0161621 0.00224279 -0.000383734 -0.0103624 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.05642e-06 -0.00279049 4 1.39824e-05 3.99957 +EDGE_SE3:QUAT 1091 1159 -6.14917 -0.599943 -0.0240799 0.00284519 9.01124e-05 -0.0118939 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.79066e-06 0.00112678 4 -7.50442e-06 3.99943 +EDGE_SE3:QUAT 1160 1161 4.23607 -0.103359 0.0229552 -0.000160935 0.000687636 0.000617865 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.35776e-07 0.00550228 4 1.69814e-06 4.00001 +EDGE_SE3:QUAT 395 1160 3.54571 2.51332 0.00930659 -0.00366356 0.000272608 0.999987 0.00349225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.87193e-06 0.0146544 4.00021 -0.000988117 0.000102717 +EDGE_SE3:QUAT 396 1160 -0.653033 2.57882 0.00166942 -0.00260101 -0.00105539 0.999969 0.00741844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.211e-05 0.0104049 4.0001 0.0043755 0.000251987 +EDGE_SE3:QUAT 397 1160 -4.87352 2.6749 0.0222681 0.000162767 -0.00370148 0.99993 0.0112768 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.63308e-06 -0.000651252 3.99995 0.0147864 0.000563435 +EDGE_SE3:QUAT 447 1160 7.1001 0.234733 0.0452709 0.00599459 -0.00339213 0.091594 0.995773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -7.09613e-05 -0.0333489 3.99992 -0.00162052 3.96672 +EDGE_SE3:QUAT 448 1160 1.91381 2.71724 0.0533285 0.00406553 -0.00480755 0.349473 0.936925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 0.000185846 -0.0473016 3.99991 -0.00880134 3.51203 +EDGE_SE3:QUAT 449 1160 -3.7307 2.29728 0.0306551 0.00475327 -0.00420094 0.558575 0.82943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 0.000329852 -0.0444172 4.00004 -0.0133727 2.75247 +EDGE_SE3:QUAT 790 1160 1.41438 4.55629 0.103906 0.00980246 0.00405672 -0.492946 0.869995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 -0.000414334 0.0699856 3.99983 -0.0206912 3.02924 +EDGE_SE3:QUAT 791 1160 -4.8775 3.72329 0.102317 0.00761529 0.00627165 -0.279074 0.960219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 -0.000169497 0.0686223 3.99973 -0.0104629 3.68965 +EDGE_SE3:QUAT 1089 1160 6.1911 -1.36965 0.0105834 0.00256265 -0.00055843 -0.048444 0.998822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.35248e-06 -0.00296428 4 5.96556e-05 3.99061 +EDGE_SE3:QUAT 1090 1160 2.08073 -0.880071 -0.00344315 0.00222419 -0.000329371 -0.00823334 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.62282e-06 -0.00241495 4 9.64467e-06 3.99973 +EDGE_SE3:QUAT 1091 1160 -1.96268 -0.786066 -0.0139831 0.0026755 0.000447181 -0.00946739 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.27534e-06 0.00388087 4 -1.88351e-05 3.99965 +EDGE_SE3:QUAT 1092 1160 -6.0476 -0.664658 0.00423815 0.00184154 0.00286944 -0.011906 0.999923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 1.90617e-05 0.0232143 3.99997 -0.000138348 3.99957 +EDGE_SE3:QUAT 1161 1162 4.2433 -0.0728516 0.0301479 -0.00265524 -0.00194353 0.00115867 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.06822e-05 -0.0155114 3.99998 -9.2193e-06 4.00005 +EDGE_SE3:QUAT 394 1161 3.55671 2.55097 0.0293262 0.00687416 0.0015551 -0.999973 0.00203187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 4.05197e-05 0.0274962 4.00075 0.00611016 0.000214866 +EDGE_SE3:QUAT 395 1161 -0.685854 2.63684 0.00439707 -0.0042458 0.000317175 0.999987 0.00289259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -4.13806e-06 0.0169833 4.00029 -0.00117054 0.00010592 +EDGE_SE3:QUAT 396 1161 -4.89405 2.74264 0.00047168 -0.00315888 -0.00127673 0.99997 0.00701714 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.77105e-05 0.0126364 4.00015 0.00528388 0.000243863 +EDGE_SE3:QUAT 448 1161 5.17091 5.41139 0.121699 0.003436 -0.00436945 0.349912 0.936766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 0.000153072 -0.0419905 3.99993 -0.00777153 3.51069 +EDGE_SE3:QUAT 449 1161 -2.04639 6.18892 0.107361 0.00412569 -0.00378662 0.55872 0.829337 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000260992 -0.0391891 4.00004 -0.0117261 2.75171 +EDGE_SE3:QUAT 790 1161 3.51533 0.856664 0.0514954 0.00991261 0.00456965 -0.49255 0.870216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 -0.000486848 0.0732317 3.99983 -0.021379 3.03092 +EDGE_SE3:QUAT 791 1161 -1.32736 1.35563 0.0508259 0.00741939 0.00693928 -0.278961 0.960249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0011 -0.000226652 0.0727299 3.99971 -0.0109704 3.69004 +EDGE_SE3:QUAT 792 1161 -5.88549 -0.598011 -0.0531555 0.0079501 6.52731e-05 -0.0183335 0.9998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 1.13181e-05 0.00227044 4 -2.61454e-05 3.99866 +EDGE_SE3:QUAT 1090 1161 6.32775 -1.03802 0.021192 0.00206524 0.000247718 -0.00786005 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.3009e-06 0.00217634 4 -8.80446e-06 3.99975 +EDGE_SE3:QUAT 1091 1161 2.29022 -0.948676 -0.000672145 0.00276706 0.000991381 -0.00894724 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.12956e-05 0.00822711 4 -3.71777e-05 3.9997 +EDGE_SE3:QUAT 1092 1161 -1.80069 -0.853179 0.00181592 0.00170741 0.00370095 -0.0114634 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 2.17274e-05 0.029838 3.99994 -0.000170916 3.9997 +EDGE_SE3:QUAT 1093 1161 -5.83854 -0.737376 -0.0548398 0.00196188 0.000265266 -0.0144804 0.999893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.49569e-06 0.0024623 4 -1.86445e-05 3.99916 +EDGE_SE3:QUAT 1162 1163 4.33042 -0.0993379 0.0121204 0.00118952 0.000298688 0.00093705 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.41256e-06 0.00237612 4 1.11371e-06 4 +EDGE_SE3:QUAT 393 1162 3.49906 2.52418 0.0163816 0.00336204 0.00514225 -0.999947 0.00829349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.85898e-05 0.01345 4.00008 0.0203434 0.000423824 +EDGE_SE3:QUAT 394 1162 -0.669428 2.62089 0.00434514 0.00513559 0.00419481 -0.999973 0.00308777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 8.46673e-05 0.0205429 4.00035 0.0166543 0.000212976 +EDGE_SE3:QUAT 395 1162 -4.94053 2.75187 -1.92412e-05 -0.00254362 -0.00224557 0.999993 0.0018656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.30625e-05 0.0101746 4.00008 0.00902046 6.01442e-05 +EDGE_SE3:QUAT 790 1162 5.64016 -2.83622 0.00350752 0.00676424 0.00444452 -0.491832 0.870652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -0.000365069 0.0569645 3.99994 -0.015913 3.03321 +EDGE_SE3:QUAT 791 1162 2.21531 -0.986782 0.00888521 0.00452593 0.00591424 -0.277727 0.960631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 -0.000185572 0.0562645 3.99984 -0.00823952 3.69226 +EDGE_SE3:QUAT 792 1162 -1.63683 -0.834428 -0.0207759 0.00523365 -0.00178057 -0.0173783 0.999834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -3.46135e-05 -0.0131465 3.99999 0.000111406 3.99884 +EDGE_SE3:QUAT 793 1162 -4.88994 -2.60806 -0.0565042 0.000561834 -0.00365632 0.247968 0.968761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 6.96723e-05 -0.0281991 3.99996 -0.00344883 3.75425 +EDGE_SE3:QUAT 1091 1162 6.51526 -1.11772 0.0204006 7.27625e-05 -0.000715887 -0.00763952 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.01798e-07 -0.00571993 4 2.18406e-05 3.99977 +EDGE_SE3:QUAT 1092 1162 2.43867 -1.03346 0.00232589 -0.000997967 0.00191423 -0.0101836 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -8.44335e-06 0.0151897 3.99999 -7.72213e-05 3.99964 +EDGE_SE3:QUAT 1093 1162 -1.60147 -0.945511 -0.0240755 -0.000588888 -0.00170466 -0.0132483 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 3.11736e-06 -0.0137274 3.99999 9.10926e-05 3.99935 +EDGE_SE3:QUAT 1094 1162 -5.75442 -0.835532 -0.0159619 0.000341097 0.000703607 -0.0162904 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 7.77607e-07 0.00569329 4 -4.65439e-05 3.99895 +EDGE_SE3:QUAT 1163 1164 4.22662 -0.107332 0.0202086 0.00314676 -0.000562999 0.00108971 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.16429e-06 -0.00454507 4 -2.4596e-06 4 +EDGE_SE3:QUAT 392 1163 3.39726 2.45441 0.0154233 0.0039296 0.0042366 -0.999917 0.0115575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 6.38391e-05 0.0157219 4.00018 0.0165787 0.000664829 +EDGE_SE3:QUAT 393 1163 -0.81436 2.55588 -0.00328594 0.00386846 0.00410871 -0.999941 0.00923696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 6.14322e-05 0.0154761 4.00018 0.0161467 0.000466349 +EDGE_SE3:QUAT 394 1163 -5.00412 2.68936 -0.0282973 0.0055557 0.00322389 -0.99997 0.00434405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 6.87949e-05 0.0222234 4.00046 0.012704 0.000239301 +EDGE_SE3:QUAT 791 1163 5.83167 -3.38687 -0.0453254 0.00567984 0.00594794 -0.276908 0.960861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 -0.000173124 0.0601371 3.99981 -0.00892449 3.69419 +EDGE_SE3:QUAT 792 1163 2.69089 -1.08742 0.00183775 0.00651673 -0.00152194 -0.0163412 0.999844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -3.48633e-05 -0.0108923 3.99999 8.58081e-05 3.99896 +EDGE_SE3:QUAT 793 1163 -1.03744 -0.611161 -0.00734573 0.00180775 -0.00315674 0.249093 0.968473 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 4.66092e-05 -0.0281216 3.99996 -0.00362409 3.75201 +EDGE_SE3:QUAT 794 1163 -4.68828 -2.20767 -0.000851524 0.00325595 -0.00136411 0.504077 0.863652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 4.95686e-05 -0.0233896 3.99998 -0.00706888 2.98376 +EDGE_SE3:QUAT 1092 1163 6.78119 -1.22589 -0.00331268 0.000164533 0.0022409 -0.0095744 0.999952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 3.21092e-07 0.0179439 3.99998 -8.5912e-05 3.99971 +EDGE_SE3:QUAT 1093 1163 2.70211 -1.16957 -0.000694611 0.000735484 -0.00142482 -0.0120661 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -4.71765e-06 -0.0112897 3.99999 6.79286e-05 3.99945 +EDGE_SE3:QUAT 1094 1163 -1.43245 -1.07462 -0.0151507 0.00148442 0.000969883 -0.0149736 0.999886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.66402e-06 0.00802314 4 -6.06921e-05 3.99912 +EDGE_SE3:QUAT 1095 1163 -5.83568 -0.951646 -0.0470104 0.00076047 0.000124662 -0.0186332 0.999826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.56226e-07 0.00116677 4 -1.13965e-05 3.99861 +EDGE_SE3:QUAT 1164 1165 4.20178 -0.0975152 0.0156758 -0.00071378 -0.00216905 0.0013651 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 6.34169e-06 -0.0173409 3.99998 -1.19145e-05 4.00007 +EDGE_SE3:QUAT 338 1164 -0.735471 6.34092 0.141612 0.0134074 0.00498576 -0.441715 0.897041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00132 -0.000454016 0.0906625 3.99959 -0.02414 3.22159 +EDGE_SE3:QUAT 391 1164 3.38542 2.373 0.0146941 0.00498213 -0.000396195 -0.999895 0.0135984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -1.59569e-05 0.0199338 4.0004 -0.00212625 0.000840159 +EDGE_SE3:QUAT 392 1164 -0.840491 2.47273 0.00294568 0.00362106 0.00122005 -0.999914 0.0125752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.38233e-05 0.0144876 4.00021 0.00451436 0.000690117 +EDGE_SE3:QUAT 393 1164 -5.07433 2.58609 -0.0249236 0.00348391 0.00109631 -0.999944 0.00991981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.24624e-05 0.0139376 4.00019 0.004108 0.000446399 +EDGE_SE3:QUAT 792 1164 6.92407 -1.32972 0.03365 0.00969218 -0.00209379 -0.0154054 0.999832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 -7.09096e-05 -0.0149508 3.99999 0.000111401 3.99911 +EDGE_SE3:QUAT 793 1164 2.72598 1.34864 0.0397841 0.00508028 -0.00295934 0.250156 0.968188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 5.46346e-06 -0.0361037 3.99992 -0.00505182 3.75001 +EDGE_SE3:QUAT 794 1164 -2.52063 1.43524 0.0402717 0.00643705 -0.000488587 0.504905 0.863151 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 3.01412e-05 -0.0348885 3.99992 -0.0118146 2.98058 +EDGE_SE3:QUAT 795 1164 -6.80585 -0.269315 0.0726525 0.00851327 0.00191553 0.659237 0.751885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 3.9349e-05 -0.0413232 3.99985 -0.0215947 2.26204 +EDGE_SE3:QUAT 1093 1164 6.94188 -1.37803 0.0275877 0.00375379 -0.00182296 -0.0109727 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.69583e-05 -0.0140866 3.99999 7.66609e-05 3.99957 +EDGE_SE3:QUAT 1094 1164 2.80548 -1.29955 -0.00790611 0.00460207 0.00051006 -0.0139155 0.999892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.16287e-05 0.00484754 4 -3.54696e-05 3.99923 +EDGE_SE3:QUAT 1095 1164 -1.60357 -1.21535 -0.0321165 0.00407512 -0.000418929 -0.0176205 0.999836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.53114e-06 -0.00248831 4 1.93982e-05 3.99876 +EDGE_SE3:QUAT 1096 1164 -5.84789 -1.21019 -0.0333316 0.00449808 0.00175234 -0.00931245 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.23057e-05 0.0145193 3.99999 -6.80339e-05 3.99971 +EDGE_SE3:QUAT 1165 1166 4.12552 -0.0815627 0.0152637 -0.002479 -0.00180188 0.000945196 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.7895e-05 -0.014387 3.99999 -6.98761e-06 4.00005 +EDGE_SE3:QUAT 337 1165 6.83033 1.2918 0.046978 0.00976981 0.0040137 -0.605414 0.79584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00084 -0.000692697 0.0698439 4.00005 -0.0254018 2.53511 +EDGE_SE3:QUAT 338 1165 1.76584 2.9534 0.0674143 0.0119154 0.0030701 -0.440539 0.897649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 -0.000185549 0.0726279 3.99969 -0.0199119 3.225 +EDGE_SE3:QUAT 339 1165 -3.51945 2.60354 0.0227966 0.00845765 0.00326285 -0.247321 0.968891 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 5.63561e-05 0.0478258 3.99984 -0.00683895 3.75589 +EDGE_SE3:QUAT 390 1165 3.45869 2.24945 0.0181282 0.00404863 0.00120459 -0.99989 0.0142104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.40253e-05 0.0161993 4.00026 0.00435613 0.000878104 +EDGE_SE3:QUAT 391 1165 -0.821522 2.34719 -0.0111676 0.00279223 0.000292266 -0.999888 0.0146864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.16311e-07 0.0111725 4.00012 0.000840472 0.000894156 +EDGE_SE3:QUAT 392 1165 -5.03229 2.44966 -0.00828217 0.00126861 0.00165703 -0.999898 0.0141429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.14607e-06 0.00507603 4.00002 0.00648134 0.000817038 +EDGE_SE3:QUAT 793 1165 6.44382 3.29958 0.0946377 0.00521179 -0.00550035 0.25142 0.967848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 0.000116235 -0.0549673 3.99983 -0.00738176 3.74791 +EDGE_SE3:QUAT 794 1165 -0.381176 5.04995 0.0902839 0.00719588 -0.00264685 0.505776 0.862631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 0.000208402 -0.0498266 3.99991 -0.015319 2.97738 +EDGE_SE3:QUAT 795 1165 -6.15633 3.90946 0.1252 0.00964646 -6.82334e-05 0.65999 0.751213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 0.000281766 -0.0544541 3.99992 -0.0252782 2.25839 +EDGE_SE3:QUAT 1094 1165 7.01689 -1.51755 0.00642287 0.0038896 -0.00177985 -0.0129303 0.999907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.70367e-05 -0.0136316 3.99999 8.70999e-05 3.99938 +EDGE_SE3:QUAT 1095 1165 2.58862 -1.44753 -0.00648709 0.00365823 -0.00262468 -0.016529 0.999853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -3.92052e-05 -0.0202634 3.99997 0.000166027 3.99901 +EDGE_SE3:QUAT 1096 1165 -1.64984 -1.37991 -0.0329179 0.00371 -0.000431004 -0.00809422 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -5.53431e-06 -0.00308729 4 1.20219e-05 3.99974 +EDGE_SE3:QUAT 1097 1165 -5.7655 -1.87437 -0.0800115 0.00282667 -0.0012619 0.0590378 0.998251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.4948e-05 -0.0120403 3.99999 -0.000374465 3.98609 +EDGE_SE3:QUAT 1166 1167 4.00114 -0.0905275 0.020585 0.00253942 0.0145574 0.00179151 0.999889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00336 0.000157327 0.116489 3.99915 0.00011748 4.00338 +EDGE_SE3:QUAT 338 1166 4.22466 -0.359102 0.0163031 0.00900916 0.0025353 -0.439374 0.898255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 -0.000123146 0.0560981 3.99982 -0.0152316 3.22858 +EDGE_SE3:QUAT 339 1166 0.0514964 0.560004 -0.00143496 0.00555868 0.00203504 -0.24623 0.969193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 2.6907e-05 0.0305839 3.99993 -0.0043733 3.75771 +EDGE_SE3:QUAT 340 1166 -4.32772 -0.530246 -0.162314 0.00330473 -0.014916 0.00410492 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00353 -0.00017615 -0.119579 3.99911 -0.000228412 4.0035 +EDGE_SE3:QUAT 389 1166 3.55957 2.10215 0.0189847 0.00578001 0.00614475 -0.999854 0.0148908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.00013418 0.0231286 4.00041 0.0238811 0.0011633 +EDGE_SE3:QUAT 390 1166 -0.646358 2.2167 -0.00222178 0.00215308 0.00363299 -0.999874 0.0153235 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.10846e-05 0.00861561 4.00003 0.0142598 0.00100865 +EDGE_SE3:QUAT 391 1166 -4.92881 2.31778 -0.0159937 0.00103299 0.00270127 -0.999871 0.0157735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.16331e-05 0.00413362 3.99999 0.0106681 0.00102794 +EDGE_SE3:QUAT 1095 1166 6.70393 -1.6665 0.0257099 0.00105883 -0.00436031 -0.015093 0.999876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -2.51541e-05 -0.034681 3.99993 0.000261739 3.99939 +EDGE_SE3:QUAT 1096 1166 2.46605 -1.52916 -0.0170771 0.00114994 -0.00229223 -0.00685521 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.13284e-05 -0.0182422 3.99998 6.25648e-05 3.9999 +EDGE_SE3:QUAT 1097 1166 -1.66589 -1.47603 -0.0440859 0.000546555 -0.00316234 0.0600427 0.998191 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 7.65803e-06 -0.0255558 3.99996 -0.000769737 3.98574 +EDGE_SE3:QUAT 1098 1166 -5.35104 -2.64753 -0.171769 0.00450609 -0.0153128 0.217572 0.975914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00385 0.00101542 -0.12541 3.9992 -0.0137519 3.81458 +EDGE_SE3:QUAT 1167 1168 4.13715 -0.0869821 0.0196292 0.000607707 -0.00310083 0.0031952 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -6.80945e-06 -0.0248304 3.99996 -3.95448e-05 4.00011 +EDGE_SE3:QUAT 339 1167 3.52516 -1.43194 -0.00608706 0.0114739 0.0157117 -0.244428 0.969472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00487 -0.00102864 0.147084 3.99883 -0.0188347 3.76642 +EDGE_SE3:QUAT 340 1167 -0.32362 -0.582755 -0.0174949 0.00576567 -0.000404849 0.00594185 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -1.08876e-05 -0.00364955 4 -1.1222e-05 3.99986 +EDGE_SE3:QUAT 341 1167 -4.08992 -1.82307 -0.0498194 0.00484264 -0.00119361 0.280907 0.959722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -2.26025e-05 -0.0239068 3.99996 -0.00406284 3.6845 +EDGE_SE3:QUAT 388 1167 3.74247 1.98785 0.0100743 0.00300716 0.00348016 -0.999886 0.0144062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.99963e-05 0.0120326 4.0001 0.0135675 0.000912383 +EDGE_SE3:QUAT 389 1167 -0.418646 2.09208 -0.00791704 0.0205609 0.00412351 -0.999638 0.0168698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99829 0.000170481 0.0822621 4.00677 0.0137386 0.00287843 +EDGE_SE3:QUAT 390 1167 -4.63372 2.18045 0.00513842 0.0170158 0.00140805 -0.999709 0.0170171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99884 -2.23009e-05 0.0680828 4.00464 0.00331662 0.00232056 +EDGE_SE3:QUAT 1096 1167 6.45445 -1.67954 0.0201311 0.00349004 0.0122157 -0.0053588 0.999905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00235 0.000152127 0.0979958 3.9994 -0.000250626 4.00228 +EDGE_SE3:QUAT 1097 1167 2.31456 -1.09492 0.00416788 0.00197368 0.0114315 0.0618775 0.998016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00199 0.000275819 0.0895035 3.99952 0.00275829 3.98669 +EDGE_SE3:QUAT 1098 1167 -1.70033 -1.02589 -0.0222014 0.00372221 -0.000536798 0.219338 0.975642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.99063e-05 -0.0134711 3.99998 -0.00182317 3.80761 +EDGE_SE3:QUAT 1099 1167 -5.35315 -2.41815 -0.0143469 0.00414675 0.00140406 0.40831 0.912833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -3.18433e-05 -0.00951572 3.99998 -0.00352009 3.33314 +EDGE_SE3:QUAT 1168 1169 4.12306 -0.0702771 0.026403 -0.000548331 -0.00177601 0.00451705 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 4.22534e-06 -0.0141781 3.99999 -3.20413e-05 3.99997 +EDGE_SE3:QUAT 340 1168 3.81337 -0.622089 0.00701913 0.00620751 -0.00356538 0.00924305 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -8.84462e-05 -0.0292076 3.99995 -0.000134089 3.99987 +EDGE_SE3:QUAT 341 1168 -0.570538 0.335189 -0.00045511 0.0063403 -0.00383598 0.284129 0.958757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 4.47318e-05 -0.0475068 3.99986 -0.00757967 3.67764 +EDGE_SE3:QUAT 342 1168 -4.54061 -0.923131 0.00946864 0.00886078 -0.000888368 0.512393 0.858705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 8.53149e-05 -0.0494527 3.99985 -0.0168451 2.95041 +EDGE_SE3:QUAT 387 1168 3.79965 1.83256 0.0219868 0.00487734 0.00127673 -0.999941 0.00966707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 1.94863e-05 0.0195119 4.00038 0.00472915 0.000474589 +EDGE_SE3:QUAT 388 1168 -0.387828 1.94656 0.0118492 6.00744e-05 0.00253001 -0.999837 0.0178706 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.51709e-06 0.000240533 3.99997 0.0101034 0.00130297 +EDGE_SE3:QUAT 389 1168 -4.57 2.03468 -0.156402 0.0176004 0.00318653 -0.999641 0.0199319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99875 7.72089e-05 0.070433 4.00497 0.00994384 0.00285491 +EDGE_SE3:QUAT 1097 1168 6.42595 -0.673799 -0.0708556 0.0026784 0.00857232 0.0649805 0.997846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00106 0.000195838 0.0660766 3.99974 0.00212556 3.9842 +EDGE_SE3:QUAT 1098 1168 2.07889 0.66379 0.0102738 0.00500988 -0.00345016 0.222474 0.97492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 5.834e-06 -0.0385136 3.9999 -0.00469894 3.80239 +EDGE_SE3:QUAT 1099 1168 -2.53521 0.603059 0.0115552 0.00611713 -0.00108571 0.411118 0.911561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 4.99642e-06 -0.0333588 3.99992 -0.00872084 3.3242 +EDGE_SE3:QUAT 1100 1168 -6.54567 -0.838987 0.0292964 0.00708887 0.00126222 0.557181 0.83036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.14573e-05 -0.031807 3.99989 -0.0135526 2.75843 +EDGE_SE3:QUAT 1169 1170 4.15503 -0.0811579 0.0215692 -0.00182119 -0.00180829 0.00163707 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.32579e-05 -0.0144305 3.99999 -1.19449e-05 4.00004 +EDGE_SE3:QUAT 341 1169 2.92814 2.49797 0.0666817 0.00603065 -0.00575342 0.288111 0.957561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 0.000171507 -0.0601245 3.99981 -0.00936318 3.66887 +EDGE_SE3:QUAT 342 1169 -2.53049 2.64294 0.0769395 0.00913458 -0.00287562 0.516559 0.856198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00059 0.000300221 -0.0610043 3.99987 -0.0194669 2.93359 +EDGE_SE3:QUAT 343 1169 -7.23065 0.997535 0.103636 0.00782567 0.00253545 0.663023 0.748554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.73527e-05 -0.0355088 3.99985 -0.0197895 2.2419 +EDGE_SE3:QUAT 386 1169 3.96197 1.72016 0.0207097 0.00427008 0.00136339 -0.999969 0.00639694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.05736e-05 0.0170813 4.00029 0.00523501 0.000243481 +EDGE_SE3:QUAT 387 1169 -0.314618 1.81352 0.00733479 0.00334069 0.00173951 -0.999888 0.0145114 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.96354e-05 0.013367 4.00017 0.00656704 0.000897786 +EDGE_SE3:QUAT 388 1169 -4.51315 1.8789 0.0297726 -0.00152274 0.00331266 -0.999746 0.0222195 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.93072e-05 -0.00609529 3.99999 0.0135049 0.00202974 +EDGE_SE3:QUAT 1098 1169 5.82724 2.38709 0.0687149 0.00450714 -0.00517238 0.226803 0.973916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 8.31209e-05 -0.0500803 3.99985 -0.00601495 3.79487 +EDGE_SE3:QUAT 1099 1169 0.252405 3.65227 0.0659414 0.00624163 -0.0029933 0.415223 0.909693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 0.000121881 -0.0455588 3.9999 -0.0110883 3.31088 +EDGE_SE3:QUAT 1100 1169 -4.91609 2.94801 0.0721972 0.0075986 -0.000729068 0.560818 0.827904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 0.000113059 -0.0437293 3.9999 -0.0164356 2.7424 +EDGE_SE3:QUAT 1170 1171 4.11277 -0.107838 0.0146464 0.000815187 -0.00417019 -0.0121024 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -1.85553e-05 -0.0332377 3.99993 0.000201249 3.99969 +EDGE_SE3:QUAT 342 1170 -0.5193 6.27959 0.16177 0.00864142 -0.00522284 0.517756 0.855469 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 0.000591738 -0.0702786 3.99994 -0.0208766 2.92895 +EDGE_SE3:QUAT 385 1170 3.85124 1.80147 0.017479 0.00250764 0.00231258 -0.999327 0.0365187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.87593e-05 0.0100515 4.00009 0.00848815 0.00537781 +EDGE_SE3:QUAT 386 1170 -0.185714 1.73874 0.00909816 0.00255321 0.00305394 -0.999959 0.00812399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.04939e-05 0.010214 4.00007 0.0120482 0.000326371 +EDGE_SE3:QUAT 387 1170 -4.4536 1.78025 0.000742087 0.00157452 0.00358514 -0.999863 0.0160663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.31812e-05 0.00630076 3.99999 0.0141291 0.00109236 +EDGE_SE3:QUAT 1099 1170 3.04873 6.74448 0.133403 0.00531426 -0.00525255 0.416333 0.909181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 0.000310832 -0.0550747 3.99991 -0.0124167 3.30742 +EDGE_SE3:QUAT 1171 1172 4.28931 -0.305949 -0.00438124 -0.00496923 0.00601196 -0.0788592 0.996855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -0.000160212 0.0429669 3.9999 -0.00163062 3.97559 +EDGE_SE3:QUAT 384 1171 3.63936 1.83009 -0.00208478 -0.00103139 0.00308029 -0.993604 0.112873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.88587e-06 -0.00416825 3.99997 0.0128499 0.051007 +EDGE_SE3:QUAT 385 1171 -0.225331 1.60135 0.00947462 -0.00152941 0.00137225 -0.999695 0.0246017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.32389e-06 -0.00612306 4.00003 0.00578158 0.00243871 +EDGE_SE3:QUAT 386 1171 -4.29272 1.78235 0.0112022 0.00176656 -0.00203913 0.999989 0.00392491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.42425e-05 -0.00706643 4.00003 0.00810086 9.05094e-05 +EDGE_SE3:QUAT 1172 1173 4.1737 -0.754582 0.0046485 -0.000598503 0.00183582 -0.187312 0.982299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.57478e-05 0.0126067 3.99999 -0.00111403 3.8597 +EDGE_SE3:QUAT 382 1172 6.52748 3.26791 0.0349942 0.0016694 0.00841907 -0.928577 0.371041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 1.84332e-05 0.0113481 4.0002 0.01839 0.550844 +EDGE_SE3:QUAT 383 1172 3.31615 1.51158 0.00593253 0.00161985 0.00824311 -0.981579 0.190871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.9201e-05 0.00728282 3.99996 0.0276254 0.145941 +EDGE_SE3:QUAT 384 1172 -0.59691 1.16991 0.00253051 0.00421803 0.00850644 -0.999368 0.0342458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000145985 0.016906 4.00006 0.0327744 0.00503149 +EDGE_SE3:QUAT 385 1172 -4.51054 1.69591 0.0178024 -0.00450799 -0.00635524 0.998515 0.0539211 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.00011826 0.0181036 4.00009 0.0271773 0.0118972 +EDGE_SE3:QUAT 1173 1174 4.02319 -0.89406 0.000418747 -0.000525172 -0.0010701 -0.208135 0.978099 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.14304e-06 -0.00928445 4 0.000991737 3.82674 +EDGE_SE3:QUAT 381 1173 6.77052 2.65742 0.0515063 0.00408055 0.00437304 -0.926534 0.376164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000157216 0.0212649 4.0004 0.00107799 0.566131 +EDGE_SE3:QUAT 382 1173 2.98517 0.93362 0.0146996 0.00164217 0.00975608 -0.981599 0.190699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000138446 0.00745938 3.9999 0.0331088 0.145766 +EDGE_SE3:QUAT 383 1173 -0.837262 0.655081 0.0033484 0.00171001 0.00922425 -0.999949 0.00371723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.53415e-05 0.00684106 3.99971 0.0368439 0.000406368 +EDGE_SE3:QUAT 384 1173 -4.80343 1.63992 -0.00807054 -0.00431658 -0.00939175 0.988051 0.153782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.09555e-05 0.0175964 3.9997 0.0405484 0.0950946 +EDGE_SE3:QUAT 1174 1175 4.22215 -0.905261 -0.0223289 0.0010685 0.000251073 -0.187507 0.982263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.67071e-06 0.00425145 4 -0.000470273 3.85937 +EDGE_SE3:QUAT 380 1174 7.19041 1.4323 0.0267474 0.00082388 0.00836255 -0.959559 0.281383 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 9.47067e-05 0.00515398 3.99997 0.0253087 0.316896 +EDGE_SE3:QUAT 381 1174 3.26958 0.495687 0.0197725 0.00177318 0.00501012 -0.984544 0.175059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.65425e-05 0.00762633 4.00004 0.0161149 0.122666 +EDGE_SE3:QUAT 382 1174 -1.08188 0.234653 0.00944919 0.00151658 -0.0101112 0.999788 0.0178616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.46171e-05 -0.00607073 3.99964 0.0401945 0.00168942 +EDGE_SE3:QUAT 383 1174 -4.85404 1.51172 0.00463076 0.00122156 -0.0100016 0.978823 0.20446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000144175 -0.00586786 3.99986 0.0339734 0.167529 +EDGE_SE3:QUAT 1175 1176 4.1467 -0.616389 -0.0375449 0.00283306 0.0140276 -0.114938 0.99327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00321 -0.000397047 0.113959 3.99922 -0.00658108 3.9504 +EDGE_SE3:QUAT 379 1175 7.23895 0.175455 -0.0237566 -0.00859703 0.0099478 -0.990347 0.137984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000376255 -0.0351547 4.00023 0.0472282 0.0770378 +EDGE_SE3:QUAT 380 1175 3.15081 -0.0901672 0.0017945 -0.000167056 0.00725898 -0.995263 0.0969501 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.49545e-05 -0.000624428 3.9998 0.0284836 0.0378022 +EDGE_SE3:QUAT 381 1175 -0.993684 -0.123553 -0.0150478 -0.00152431 -0.00446072 0.999916 0.0120993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.58838e-05 0.00609868 3.99995 0.0179839 0.000675741 +EDGE_SE3:QUAT 382 1175 -5.27348 1.28504 0.035657 0.00341163 -0.00818507 0.978732 0.204952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -7.63763e-05 -0.0150426 4.00024 0.023997 0.168235 +EDGE_SE3:QUAT 1176 1177 4.24392 -0.3237 0.011474 0.00333086 0.00271519 -0.0385853 0.999246 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 3.1912e-05 0.0232141 3.99997 -0.000456849 3.99418 +EDGE_SE3:QUAT 378 1176 7.29744 -0.444153 0.0433722 0.00466467 0.0113843 -0.999549 0.0274118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000223921 0.0186848 3.9999 0.0444329 0.00358692 +EDGE_SE3:QUAT 379 1176 3.09319 -0.377517 0.0125525 0.00453315 0.00787996 -0.999692 0.023105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.00014176 0.0181492 4.00012 0.0306432 0.00245262 +EDGE_SE3:QUAT 380 1176 -1.01188 -0.280083 -0.0317138 -0.0131852 -0.00574554 0.999727 0.01844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 0.000374155 0.0527665 4.00258 0.0249304 0.00221184 +EDGE_SE3:QUAT 381 1176 -5.10925 0.583239 -0.0561145 -0.0148317 -0.00142924 0.991748 0.127337 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99927 0.000714466 0.0607291 4.00322 0.0203782 0.0658994 +EDGE_SE3:QUAT 1177 1178 4.32958 -0.139477 0.030391 0.00349071 -0.00679397 -0.00272427 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -9.76635e-05 -0.0542448 3.99982 7.77271e-05 4.00071 +EDGE_SE3:QUAT 377 1177 7.06973 -0.442448 0.0644813 -0.0103523 -0.00990937 0.999838 0.0109123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000429572 0.0414212 4.00127 0.0405507 0.00131625 +EDGE_SE3:QUAT 378 1177 3.05126 -0.35815 0.0231341 -0.006865 -0.00813462 0.999881 0.0111548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000229756 0.0274673 4.00046 0.0331481 0.000961042 +EDGE_SE3:QUAT 379 1177 -1.13087 -0.249046 -0.00375623 -0.00685909 -0.00472633 0.999858 0.0146475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000143225 0.0274456 4.00064 0.0197036 0.00114362 +EDGE_SE3:QUAT 380 1177 -5.22125 0.170515 -0.139037 -0.0156234 -0.00318604 0.998248 0.0569804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99909 0.00051705 0.0627895 4.00369 0.0197674 0.0140737 +EDGE_SE3:QUAT 1178 1179 4.34549 -0.0953292 0.00590092 -0.000968933 -0.00195563 0.00251305 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 7.79092e-06 -0.0156159 3.99998 -1.96989e-05 4.00004 +EDGE_SE3:QUAT 376 1178 6.86523 -0.322254 0.0413854 -0.00556043 -0.00346216 0.999874 0.014441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.61075e-05 0.0222488 4.00043 0.014486 0.00101041 +EDGE_SE3:QUAT 377 1178 2.75545 -0.221807 0.00313167 -0.00324706 -0.00665614 0.999879 0.0136844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.48117e-05 0.0129926 3.99998 0.0269683 0.000973113 +EDGE_SE3:QUAT 378 1178 -1.25265 -0.13687 -0.00341246 6.0578e-05 -0.00481712 0.999896 0.0136014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.68532e-06 -0.000242497 3.99991 0.0192527 0.000832689 +EDGE_SE3:QUAT 379 1178 -5.4303 0.0103171 -0.0344923 8.07941e-05 -0.00144325 0.999848 0.0173956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.50924e-07 -0.000323385 3.99999 0.0057574 0.00121874 +EDGE_SE3:QUAT 1179 1180 4.00986 -0.0585926 -0.00340355 -0.00387237 0.000234206 0.00627861 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.37013e-06 0.00216524 4 7.0961e-06 3.99984 +EDGE_SE3:QUAT 375 1179 6.83193 -0.192241 0.0698424 -0.00667602 -0.0031128 0.999903 0.0117795 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 9.46757e-05 0.0267095 4.00066 0.013079 0.000776172 +EDGE_SE3:QUAT 376 1179 2.54166 -0.103237 0.00200651 -0.00351149 -0.00456851 0.999919 0.011315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.55049e-05 0.014049 4.00011 0.018587 0.000647839 +EDGE_SE3:QUAT 377 1179 -1.54996 -0.0114164 -0.0156566 -0.00132617 -0.00766394 0.999909 0.0110312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.58565e-05 0.00530599 3.99979 0.0307628 0.00073042 +EDGE_SE3:QUAT 378 1179 -5.53629 0.0675445 0.00507468 0.00216171 -0.00589068 0.99992 0.010964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.26505e-05 -0.00864887 3.99994 0.0233663 0.000636049 +EDGE_SE3:QUAT 1180 1181 4.3935 -0.0623322 0.0151821 0.00144814 0.0051372 0.00918073 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 3.53889e-05 0.0409364 3.9999 0.000188624 4.00008 +EDGE_SE3:QUAT 374 1180 7.08289 -0.132538 0.00641749 -0.000855541 -0.00764102 0.999955 0.00557492 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.36274e-05 0.00342259 3.99978 0.0305991 0.000361343 +EDGE_SE3:QUAT 375 1180 2.8246 -0.0325144 0.0107584 -0.00683715 -0.00694632 0.999938 0.00545355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000193999 0.0273512 4.00054 0.028088 0.000503196 +EDGE_SE3:QUAT 376 1180 -1.43909 0.0460135 -0.0303676 -0.00382214 -0.00858293 0.999943 0.00507358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000129962 0.0152907 3.99993 0.034486 0.000458745 +EDGE_SE3:QUAT 377 1180 -5.52959 0.118799 -0.0255348 -0.00179787 -0.011527 0.99992 0.00488589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.80323e-05 0.0071931 3.99952 0.0461734 0.000641492 +EDGE_SE3:QUAT 1181 1182 4.46918 -0.0575529 0.0374239 0.000557202 0.00470439 0.00738742 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 1.43848e-05 0.0375856 3.99991 0.000139093 4.00013 +EDGE_SE3:QUAT 373 1181 6.91859 -0.113675 -0.0201843 -0.000513683 0.00478874 -0.999984 0.0031239 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.28435e-06 -0.00205483 3.99991 0.0191671 0.000131938 +EDGE_SE3:QUAT 374 1181 2.68737 -0.0268407 0.0144346 0.00595184 0.00638915 -0.999957 0.00325924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.00015044 0.0238087 4.00041 0.0254052 0.000345541 +EDGE_SE3:QUAT 375 1181 -1.54546 0.0678058 -0.0354183 0.0121421 0.005419 -0.999905 0.00351141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99941 0.000252065 0.0485678 4.00225 0.0213513 0.000752996 +EDGE_SE3:QUAT 376 1181 -5.80497 0.154512 -0.0464413 0.00907354 0.00708269 -0.999926 0.00403519 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000250911 0.0362962 4.00113 0.0280488 0.000591116 +EDGE_SE3:QUAT 1182 1183 4.54329 -0.0796867 0.0292503 -0.000354659 -0.00112826 0.0045944 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.73582e-06 -0.00900629 3.99999 -2.06851e-05 3.99994 +EDGE_SE3:QUAT 372 1182 6.83761 -0.259579 0.0198369 0.00477881 0.00704077 -0.999961 0.00225995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000134263 0.0191166 4.00017 0.0280792 0.000308887 +EDGE_SE3:QUAT 373 1182 2.47498 -0.0844691 0.0257232 0.00435804 0.00442281 -0.999922 0.0108402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 7.37277e-05 0.0174356 4.00024 0.0173098 0.000620958 +EDGE_SE3:QUAT 374 1182 -1.75488 0.00796645 -0.00391583 0.0107293 0.00600373 -0.999867 0.0107039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.0002311 0.0429239 4.00173 0.0231037 0.00105239 +EDGE_SE3:QUAT 375 1182 -5.9779 0.111654 -0.100383 0.0171153 0.0051497 -0.999779 0.0110845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99881 0.000277639 0.0684655 4.00463 0.019105 0.00175495 +EDGE_SE3:QUAT 1183 1184 4.40594 -0.0939332 0.00629055 0.00102705 -0.00135193 0.00229636 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.47231e-06 -0.0108437 3.99999 -1.24163e-05 4.00001 +EDGE_SE3:QUAT 371 1183 6.53654 -0.426678 0.0387989 -0.0052976 -0.0062802 0.999947 0.00621288 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000135263 0.0211926 4.00028 0.025385 0.000427774 +EDGE_SE3:QUAT 372 1183 2.29157 -0.218142 0.00925483 0.00362179 0.00706304 -0.999947 0.00652689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000102813 0.0144891 4.00002 0.0280614 0.000419751 +EDGE_SE3:QUAT 373 1183 -2.04139 -0.0964319 0.0133052 0.00318453 0.00468362 -0.999871 0.0150556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.84273e-05 0.0127429 4.00009 0.0183413 0.00103141 +EDGE_SE3:QUAT 374 1183 -6.24059 -0.0175487 -0.0650214 0.00965477 0.00606889 -0.999815 0.0154624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000203739 0.0386329 4.00139 0.0230786 0.00146272 +EDGE_SE3:QUAT 1184 1185 4.48704 -0.101918 -0.0124072 0.00332046 0.00025637 0.00252276 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.18612e-06 0.00195039 4 2.42274e-06 3.99998 +EDGE_SE3:QUAT 370 1184 6.52703 -0.48938 0.0446298 -0.00311916 -0.0092392 0.999787 0.018167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.00010651 0.0124839 3.99979 0.0373796 0.00170857 +EDGE_SE3:QUAT 371 1184 2.1657 -0.273531 0.00396779 -0.00372128 -0.00524116 0.999972 0.00376179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.84317e-05 0.014886 4.00011 0.0210772 0.000223061 +EDGE_SE3:QUAT 372 1184 -2.07712 -0.161957 -0.0153512 0.00214494 0.00607408 -0.999937 0.00913933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.37319e-05 0.00858134 3.99993 0.0241346 0.000498154 +EDGE_SE3:QUAT 373 1184 -6.39817 -0.128811 -0.011441 0.00198823 0.00379651 -0.99983 0.0179229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.04035e-05 0.00795706 4.00001 0.0148891 0.0013562 +EDGE_SE3:QUAT 1185 1186 4.11728 -0.0854491 0.0168613 -0.000120754 -0.00393029 0.00216842 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 2.70236e-06 -0.0314406 3.99994 -3.41374e-05 4.00023 +EDGE_SE3:QUAT 369 1185 6.06494 -0.364225 0.0446918 -0.00682407 -0.00525774 0.999759 0.020213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000160774 0.0273134 4.0006 0.0221177 0.00194316 +EDGE_SE3:QUAT 370 1185 2.05541 -0.247873 0.0115259 -0.00329668 -0.00567969 0.999862 0.015257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.46677e-05 0.0131918 4.00003 0.0231088 0.00110815 +EDGE_SE3:QUAT 371 1185 -2.31721 -0.139611 -0.0388235 -0.00410334 -0.00169593 0.999989 0.00138433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.83691e-05 0.0164133 4.00026 0.00682976 8.66766e-05 +EDGE_SE3:QUAT 372 1185 -6.53345 -0.150158 -0.0490784 0.00273897 0.00281693 -0.999918 0.0121787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.9372e-05 0.0109584 4.00009 0.0109971 0.000653542 +EDGE_SE3:QUAT 1186 1187 4.17925 -0.0781549 0.0222259 -0.0030172 0.00558784 -0.0043062 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -7.03603e-05 0.0445498 3.99988 -9.80873e-05 4.00042 +EDGE_SE3:QUAT 368 1186 6.33191 -0.136191 -0.028021 0.00251452 -0.00440765 0.99992 0.0115772 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.42818e-05 -0.0100604 4.00003 0.0173923 0.00063706 +EDGE_SE3:QUAT 369 1186 1.95717 -0.108972 0.00520751 -0.00301579 -0.0058734 0.999815 0.0180527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.94487e-05 0.0120694 3.99999 0.0239106 0.001483 +EDGE_SE3:QUAT 370 1186 -2.0131 -0.0271924 0.00111373 0.000579415 -0.00593611 0.999895 0.0131796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.7325e-05 -0.00231851 3.99987 0.0236727 0.000836281 +EDGE_SE3:QUAT 371 1186 -6.40756 -0.0345192 -0.0524023 0.000227501 0.00219682 -0.999997 0.00117183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.04285e-06 0.000910014 3.99998 0.0087851 2.49944e-05 +EDGE_SE3:QUAT 1187 1188 4.02218 -0.149343 0.0368208 -0.000901306 -0.00685553 -0.0185235 0.999805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 3.83125e-06 -0.0550254 3.99981 0.000509393 3.99938 +EDGE_SE3:QUAT 367 1187 6.40301 0.0823979 0.0333795 -0.00886099 -0.00625598 0.999934 0.00375051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000227806 0.0354455 4.00109 0.0252993 0.000530336 +EDGE_SE3:QUAT 368 1187 2.15136 0.0455645 0.0152193 -0.00297716 -0.00758808 0.999836 0.0161533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.59883e-05 0.011914 3.99989 0.0307176 0.00131517 +EDGE_SE3:QUAT 369 1187 -2.2099 0.120293 0.00860149 -0.00863271 -0.00870681 0.999682 0.0220528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000324626 0.0345587 4.00081 0.0363199 0.00257386 +EDGE_SE3:QUAT 370 1187 -6.18135 0.159991 0.0292953 -0.00522093 -0.00883341 0.999791 0.0176693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000184125 0.0208954 4.00009 0.0360474 0.00168293 +EDGE_SE3:QUAT 1188 1189 4.40752 -0.254506 0.00676733 -0.00525289 -0.00132049 -0.0542873 0.998511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 3.60061e-05 -0.0139322 3.99999 0.000408371 3.98826 +EDGE_SE3:QUAT 366 1188 6.47902 0.583522 0.0389379 0.00641496 0.000827473 -0.999783 0.0198241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 1.65114e-06 0.0256745 4.00066 0.00229013 0.00173816 +EDGE_SE3:QUAT 367 1188 2.38906 0.269221 0.00478194 -0.00197469 -0.00724681 0.999722 0.0223556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.94988e-05 0.00790461 3.99984 0.0293038 0.00222951 +EDGE_SE3:QUAT 368 1188 -1.84337 0.322246 0.0353009 0.00407211 -0.00876261 0.99937 0.0341457 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000147396 -0.0163213 4.00002 0.0338396 0.00501703 +EDGE_SE3:QUAT 369 1188 -6.21647 0.459022 -0.0187265 -0.00140262 -0.00982222 0.99911 0.041003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.41413e-05 0.00561971 3.99962 0.0395814 0.00712523 +EDGE_SE3:QUAT 1189 1190 4.03443 -0.407763 -0.0143595 -0.00520397 0.0199441 -0.0993601 0.994838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0056 -0.00126452 0.151206 3.99869 -0.00744527 3.96621 +EDGE_SE3:QUAT 365 1189 6.26055 1.37568 -0.0501704 -0.0121543 0.00683292 -0.99833 0.0560533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -0.000493166 -0.0488395 4.00194 0.0325747 0.0134318 +EDGE_SE3:QUAT 366 1189 2.0696 0.661364 -0.0050018 -0.0049141 -0.00643738 0.999387 0.0340726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000132682 0.0196898 4.00017 0.0270154 0.00492345 +EDGE_SE3:QUAT 367 1189 -1.97398 0.716429 -0.00358324 -0.000309374 -0.0133137 0.997038 0.0757513 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.95035e-05 0.00120073 3.99931 0.0526742 0.0236512 +EDGE_SE3:QUAT 368 1189 -6.2077 0.893472 0.085117 0.00556823 -0.0142907 0.995963 0.0884487 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000353478 -0.0226168 4.00005 0.0521478 0.0321078 +EDGE_SE3:QUAT 1190 1191 4.21535 -0.767156 0.0238517 0.00220279 -0.00237646 -0.172064 0.98508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.75814e-05 -0.0137151 3.99999 0.00102505 3.88162 +EDGE_SE3:QUAT 364 1190 5.88482 2.72215 0.0341764 0.00609721 0.0127793 -0.991002 0.133094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000270365 0.0252711 4.00048 0.0425021 0.071481 +EDGE_SE3:QUAT 365 1190 2.21194 1.32114 0.024312 -0.00676225 -0.0120222 0.998925 0.044251 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000312748 0.027126 3.99999 0.0502492 0.00864926 +EDGE_SE3:QUAT 366 1190 -1.91133 1.35438 -0.0527253 -0.0241693 -0.0114429 0.990658 0.133724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99851 0.00248932 0.0990727 4.00669 0.069322 0.0752318 +EDGE_SE3:QUAT 367 1190 -5.88556 1.72018 -0.000381322 -0.0193349 -0.0166669 0.984231 0.175038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 0.00182603 0.0801661 4.00204 0.0879592 0.126171 +EDGE_SE3:QUAT 1191 1192 4.34417 -0.892108 -0.00201455 0.00346846 -0.00270299 -0.182993 0.983104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.32232e-05 -0.0131001 4 0.00093283 3.86609 +EDGE_SE3:QUAT 363 1191 4.78928 3.59261 0.0402052 0.00562004 0.0115235 -0.98465 0.174069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000172817 0.0239647 4.00057 0.0350599 0.12167 +EDGE_SE3:QUAT 364 1191 1.62801 2.35447 0.0121509 -0.00162979 -0.0111632 0.999175 0.0390106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.4845e-05 0.00652953 3.99952 0.0449881 0.00660477 +EDGE_SE3:QUAT 365 1191 -1.90563 2.46282 0.0272094 -0.00207268 -0.0105437 0.976482 0.215331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000106426 0.00800412 3.99957 0.0407685 0.185924 +EDGE_SE3:QUAT 366 1191 -5.75488 3.21525 -0.193232 -0.0191322 -0.0134575 0.953096 0.301763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 0.00162206 0.0833625 4.00098 0.0840121 0.367942 +EDGE_SE3:QUAT 1192 1193 4.28582 -0.746128 -0.00137011 0.00111826 0.00761296 -0.148012 0.988956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 -0.000173982 0.0608829 3.99979 -0.00450573 3.9133 +EDGE_SE3:QUAT 362 1192 3.25163 3.59095 -0.0256334 -0.000727027 0.00480484 -0.978224 0.207497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.38439e-05 -0.00274629 3.99991 0.0183368 0.172309 +EDGE_SE3:QUAT 363 1192 0.411921 2.92579 -0.0105607 -0.0013533 -0.00839278 0.999923 0.00901014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.06879e-05 0.00541433 3.99974 0.0336609 0.000615365 +EDGE_SE3:QUAT 364 1192 -2.63981 3.5597 0.0293986 0.00328177 -0.00746416 0.975146 0.221415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -5.01307e-05 -0.0147043 4.00025 0.0207349 0.196274 +EDGE_SE3:QUAT 1193 1194 3.95451 -0.477959 0.0116389 0.00547414 -0.00349033 -0.0806935 0.996718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.30508e-05 -0.0223719 3.99997 0.000828881 3.97408 +EDGE_SE3:QUAT 360 1193 5.13771 3.98881 0.00741059 0.00121222 0.00638096 -0.882791 0.469722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -4.86355e-05 0.0114596 4.00018 0.00903961 0.882645 +EDGE_SE3:QUAT 361 1193 2.16981 2.61325 -0.00257337 0.000224245 0.0064913 -0.96102 0.276401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.11433e-05 0.00209059 3.99994 0.020683 0.305712 +EDGE_SE3:QUAT 362 1193 -0.95876 2.52758 -0.0239723 0.00623638 0.00520893 -0.998161 0.0600797 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 7.96499e-05 0.0250891 4.0006 0.0176652 0.0146746 +EDGE_SE3:QUAT 363 1193 -3.8469 3.74226 -0.00841723 -0.00757198 -0.00735421 0.987459 0.15752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000282909 0.0311686 4.00027 0.0369192 0.0998451 +EDGE_SE3:QUAT 1194 1195 4.0258 -0.144396 0.0146636 2.16875e-05 0.000119537 -0.00874504 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.39144e-09 0.000958465 4 -4.19406e-06 3.99969 +EDGE_SE3:QUAT 359 1194 6.31937 2.64956 0.0513837 0.00509668 -0.00319484 -0.820215 0.572023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.24311e-05 0.0228817 3.99992 -0.0193134 1.30911 +EDGE_SE3:QUAT 360 1194 2.5242 0.968121 -0.00615247 0.000404774 -6.11949e-06 -0.917856 0.396913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.12046e-06 0.00195128 4 -0.00109819 0.630161 +EDGE_SE3:QUAT 361 1194 -1.42942 0.935387 -0.00790192 -0.00210658 0.00052058 -0.980191 0.198041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.09808e-05 -0.00887499 4.00005 0.0050877 0.156908 +EDGE_SE3:QUAT 362 1194 -4.91748 2.5218 -0.0557922 -0.00271939 0.000150683 0.999778 0.020915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.07764e-06 0.0108847 4.00012 -0.000147265 0.00177938 +EDGE_SE3:QUAT 1195 1196 4.10422 -0.0731571 0.0219209 -0.000812745 -0.000964099 0.00103135 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.15181e-06 -0.00770274 4 -3.98849e-06 4.00001 +EDGE_SE3:QUAT 359 1195 4.78447 -1.08264 0.0445963 0.00508507 -0.0029873 -0.825286 0.564685 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.50192e-05 0.0231901 3.99993 -0.0192187 1.27575 +EDGE_SE3:QUAT 360 1195 -0.352427 -1.87028 0.00194339 0.000458679 0.000281111 -0.921286 0.388885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.89827e-06 0.00233382 4 -0.000488582 0.604929 +EDGE_SE3:QUAT 361 1195 -5.20196 -0.496825 0.0223173 -0.00180509 0.00040116 -0.981936 0.189202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.49272e-05 -0.00757583 4.00004 0.00409733 0.143209 +EDGE_SE3:QUAT 1117 1195 1.11011 5.02643 0.11627 0.0116625 0.00450615 -0.434862 0.90041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00103 -0.000344321 0.0795348 3.99968 -0.0207568 3.24515 +EDGE_SE3:QUAT 1118 1195 -5.18128 4.2592 0.0795806 0.00833713 0.00546608 -0.243467 0.969858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -3.60127e-05 0.0633051 3.99974 -0.00852089 3.76389 +EDGE_SE3:QUAT 1196 1197 4.04667 -0.0767661 0.0133048 -0.00108005 -0.00153911 0.00107019 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 6.70022e-06 -0.012299 3.99999 -6.64013e-06 4.00003 +EDGE_SE3:QUAT 359 1196 3.23335 -4.86879 0.042046 0.00381075 -0.00265208 -0.824697 0.565556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.75362e-07 0.016775 3.99995 -0.0148785 1.27957 +EDGE_SE3:QUAT 360 1196 -3.25655 -4.71978 0.028424 -0.000581567 0.000594818 -0.920807 0.390018 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.54197e-07 -0.00251141 4 0.00306288 0.60846 +EDGE_SE3:QUAT 1117 1196 3.58994 1.77192 0.0612771 0.0104795 0.00392983 -0.433704 0.900986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0008 -0.000261197 0.070718 3.99974 -0.0184584 3.24884 +EDGE_SE3:QUAT 1118 1196 -1.58527 2.22801 0.0383708 0.00715673 0.00472496 -0.242413 0.970135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 -2.6805e-05 0.0545274 3.99981 -0.00730348 3.76568 +EDGE_SE3:QUAT 1119 1196 -6.60086 0.980927 -0.165239 0.0046047 -0.00970436 -0.0727185 0.997295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00125 -0.000314672 -0.0730336 3.99969 0.00261118 3.98018 +EDGE_SE3:QUAT 1197 1198 4.02156 -0.0874197 -0.0174916 0.000921517 0.0113717 0.00201992 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00207 4.82493e-05 0.0909921 3.99948 9.48761e-05 4.00205 +EDGE_SE3:QUAT 1117 1197 6.04081 -1.42633 0.00515332 0.00884435 0.00325169 -0.432848 0.901418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 -0.00017825 0.0592681 3.99982 -0.0154683 3.25144 +EDGE_SE3:QUAT 1118 1197 1.92354 0.270656 0.00334952 0.00588415 0.0035938 -0.241277 0.970432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -6.78145e-06 0.0426554 3.99988 -0.005722 3.76759 +EDGE_SE3:QUAT 1119 1197 -2.64886 0.322354 -0.0750933 0.00341908 -0.0110181 -0.0717992 0.997352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00174 -0.00033931 -0.084559 3.99958 0.00300524 3.98117 +EDGE_SE3:QUAT 1120 1197 -6.93745 -0.350402 -0.0861113 0.00398222 -0.0110441 0.010821 0.999873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00191 -0.000145574 -0.0888904 3.9995 -0.000470694 4.00151 +EDGE_SE3:QUAT 1198 1199 4.38054 -0.0780974 0.0211697 -0.00249702 -0.00103484 0.00229261 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.02798e-05 -0.00820992 4 -9.44821e-06 4 +EDGE_SE3:QUAT 1118 1198 5.46901 -1.69925 -0.0549821 0.0095683 0.0144371 -0.239301 0.970791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.004 -0.000866705 0.132272 3.99906 -0.0164899 3.77531 +EDGE_SE3:QUAT 1119 1198 1.31628 -0.348472 -0.0102042 0.00496222 0.000167005 -0.0695305 0.997567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 1.64127e-05 0.00545322 4 -0.000237411 3.98067 +EDGE_SE3:QUAT 1120 1198 -2.91096 -0.353336 -0.0144171 0.00466557 0.000436525 0.0129141 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 5.93637e-06 0.00276829 4 1.63317e-05 3.99933 +EDGE_SE3:QUAT 1121 1198 -7.30462 -0.485912 -0.0272671 0.00186267 0.000805256 0.0420116 0.999115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.32543e-06 0.00548704 4 0.000108588 3.99295 +EDGE_SE3:QUAT 1199 1200 4.36937 -0.107743 0.0203208 -0.00135716 -0.00116437 -0.0075371 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 6.18114e-06 -0.00943697 3.99999 3.56723e-05 3.9998 +EDGE_SE3:QUAT 964 1199 5.53707 -4.43197 0.0637921 -0.00781672 -0.00481842 0.95508 0.296205 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000289983 0.034107 4.00025 0.0320807 0.351526 +EDGE_SE3:QUAT 965 1199 -0.823029 -5.26179 0.0452008 -0.00444821 -0.00204829 0.874396 0.485188 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 6.88871e-05 0.0210125 4.00001 0.0169926 0.941835 +EDGE_SE3:QUAT 1119 1199 5.65395 -1.03011 0.00560663 0.00245497 -0.000601158 -0.0674774 0.997718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.86863e-06 -0.0027946 4 7.15692e-05 3.98179 +EDGE_SE3:QUAT 1120 1199 1.47121 -0.306495 0.00209819 0.00216001 -0.000674832 0.015321 0.99988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.21255e-06 -0.00579379 4 -4.53662e-05 3.99907 +EDGE_SE3:QUAT 1121 1199 -2.9315 -0.197772 -0.0124875 -0.000584682 -0.000392471 0.0440551 0.999029 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.32289e-07 -0.00282194 4 -5.98254e-05 3.99224 +EDGE_SE3:QUAT 1122 1199 -6.92407 -0.0767056 0.0190282 -0.00371048 0.00337405 0.0430437 0.999061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -4.15841e-05 0.0288324 3.99995 0.000632689 3.9928 +EDGE_SE3:QUAT 1200 1201 4.19213 -0.20359 0.019989 0.00178183 -0.00149595 -0.0371888 0.999306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.14803e-05 -0.0111484 3.99999 0.000202305 3.9945 +EDGE_SE3:QUAT 963 1200 6.7392 -0.190111 0.052985 -0.00742614 -0.00260828 0.994862 0.100937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000190916 0.0301342 4.00074 0.0161085 0.0410476 +EDGE_SE3:QUAT 964 1200 2.00006 -1.88422 0.032195 -0.00733186 -0.0067171 0.952886 0.303166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000195013 0.0315914 3.99998 0.037047 0.368267 +EDGE_SE3:QUAT 965 1200 -3.03433 -1.5175 0.045555 -0.00412316 -0.00378598 0.870765 0.491667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.93366e-06 0.0177053 3.99992 0.0191083 0.967146 +EDGE_SE3:QUAT 966 1200 -7.47992 0.015502 0.0808578 -0.00365891 0.000814197 0.793632 0.608386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 0.000112342 0.0216815 4.00007 0.0105461 1.4807 +EDGE_SE3:QUAT 1060 1200 4.82484 3.72902 0.118873 0.00659805 0.00734942 -0.496318 0.868085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00109 -0.000755261 0.0713339 4.00001 -0.0186997 3.01594 +EDGE_SE3:QUAT 1061 1200 -1.45659 4.54547 0.0702244 0.000306628 0.00610133 -0.289726 0.95709 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 -0.000221636 0.0438064 3.99994 -0.00608365 3.66471 +EDGE_SE3:QUAT 1120 1200 5.84256 -0.289359 0.0280132 0.000808092 -0.00177384 0.00753618 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -5.19905e-06 -0.0142627 3.99999 -5.37738e-05 3.99982 +EDGE_SE3:QUAT 1121 1200 1.43231 0.0836775 0.00764281 -0.00220644 -0.00157892 0.0364708 0.999331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.44042e-05 -0.0116414 3.99999 -0.000206384 3.99471 +EDGE_SE3:QUAT 1122 1200 -2.56782 0.183501 0.0101771 -0.00495595 0.00217456 0.0354298 0.999358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.51558e-05 0.0194688 3.99997 0.00035648 3.99507 +EDGE_SE3:QUAT 1123 1200 -6.55346 0.328641 0.0118872 -0.00395986 0.00360534 0.0291883 0.99956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -5.08943e-05 0.0301929 3.99994 0.000445941 3.99682 +EDGE_SE3:QUAT 1201 1202 4.06944 -0.390142 0.0158077 0.00218307 0.00307256 -0.0954962 0.995423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 5.17009e-06 0.0267324 3.99995 -0.00131042 3.9637 +EDGE_SE3:QUAT 962 1201 6.35251 2.3889 -0.0104094 0.000202097 0.00405225 -0.998781 0.0491927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.49305e-06 0.000815219 3.99994 0.0160316 0.00974426 +EDGE_SE3:QUAT 963 1201 2.66523 0.846686 0.0193108 -0.00585409 -0.000854753 0.990373 0.138295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000123072 0.0240605 4.00048 0.00961142 0.0766723 +EDGE_SE3:QUAT 964 1201 -1.29816 0.697379 0.0185361 -0.00496972 -0.0052391 0.940906 0.33859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.71034e-05 0.0213677 3.99991 0.0271155 0.458894 +EDGE_SE3:QUAT 965 1201 -5.03588 2.17638 0.057346 -0.00168208 -0.00287196 0.851724 0.523981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.01527e-05 0.0055721 3.99997 0.00952674 1.09827 +EDGE_SE3:QUAT 1060 1201 6.77822 0.0185552 0.0606153 0.00758246 0.0053512 -0.528467 0.848903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 -0.000578144 0.0653423 3.99999 -0.0193808 2.88395 +EDGE_SE3:QUAT 1061 1201 1.94802 2.02774 0.0385536 0.00154 0.00421847 -0.325241 0.945621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -0.000122813 0.0341259 3.99996 -0.00556022 3.57716 +EDGE_SE3:QUAT 1062 1201 -2.98916 1.92962 0.0235727 0.00206268 0.00296729 -0.154086 0.988051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -1.1059e-05 0.0266525 3.99996 -0.00212891 3.90521 +EDGE_SE3:QUAT 1121 1201 5.64795 0.184478 0.0464823 -1.28155e-05 -0.00305389 -0.000818193 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -2.65761e-08 -0.024432 3.99996 9.99316e-06 4.00015 +EDGE_SE3:QUAT 1122 1201 1.63594 0.277904 0.0116533 -0.00310923 0.000641795 -0.00175624 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.86297e-06 0.00506874 4 -4.46189e-06 3.99999 +EDGE_SE3:QUAT 1123 1201 -2.35685 0.368975 0.0126969 -0.0019975 0.00230591 -0.00821875 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.9192e-05 0.0182487 3.99998 -7.49728e-05 3.99981 +EDGE_SE3:QUAT 1124 1201 -6.42425 0.463552 -0.0619822 -0.00358692 -0.00229749 -0.0078461 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.27463e-05 -0.0187159 3.99998 7.33992e-05 3.99984 +EDGE_SE3:QUAT 1202 1203 4.26227 -0.745608 0.00132133 -0.0023686 0.000349738 -0.179576 0.983741 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.7507e-06 -0.00233073 4 0.000366102 3.87101 +EDGE_SE3:QUAT 961 1202 5.08104 3.99224 0.0217651 0.00594301 -7.57176e-05 -0.983258 0.182124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000145978 0.0249216 4.00051 -0.00865174 0.132856 +EDGE_SE3:QUAT 962 1202 2.27642 2.37426 0.00561813 -0.00311643 -0.00190515 0.998906 0.0466129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.24098e-05 0.0125048 4.00013 0.00873927 0.00874936 +EDGE_SE3:QUAT 963 1202 -1.1202 2.34623 -0.00364504 -0.00859868 0.00144064 0.972559 0.232495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000360477 0.037214 4.00112 0.0101359 0.216604 +EDGE_SE3:QUAT 964 1202 -4.14439 3.58079 0.0228767 -0.00666901 -0.0025816 0.904167 0.427119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 0.000210925 0.0313147 4.00013 0.0245629 0.730155 +EDGE_SE3:QUAT 1061 1202 4.87992 -0.767014 0.0219339 0.00434099 0.0066088 -0.414224 0.910141 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 -0.000433248 0.0589858 3.99994 -0.0126203 3.31454 +EDGE_SE3:QUAT 1062 1202 0.760107 0.323526 0.0166511 0.00486458 0.00578721 -0.247712 0.968804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -0.00013398 0.0559803 3.99983 -0.00734303 3.75534 +EDGE_SE3:QUAT 1063 1202 -3.63513 0.171259 0.0154935 0.000311605 0.00381452 -0.14352 0.98964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -4.49195e-05 0.030109 3.99995 -0.00215078 3.91783 +EDGE_SE3:QUAT 1122 1202 5.69131 -0.119723 0.029798 -0.000544136 0.00341218 -0.0974098 0.995238 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -3.28387e-05 0.0262788 3.99996 -0.00126352 3.96222 +EDGE_SE3:QUAT 1123 1202 1.68354 -0.0895293 0.0101031 -7.65509e-05 0.00507292 -0.103457 0.994621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -6.39419e-05 0.0398426 3.99991 -0.00204864 3.95758 +EDGE_SE3:QUAT 1124 1202 -2.37384 0.000216229 -0.0161017 -0.000722135 0.000429932 -0.103176 0.994663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.07151e-06 0.00249695 4 -0.000112489 3.95742 +EDGE_SE3:QUAT 1125 1202 -6.75149 0.0783477 -0.0184433 -0.00234048 0.0019663 -0.100161 0.994967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.04153e-05 0.0127 3.99999 -0.00058526 3.95991 +EDGE_SE3:QUAT 1203 1204 4.02279 -0.82531 0.0182229 -0.00344733 -0.00324938 -0.196797 0.980433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -1.27436e-05 -0.0324322 3.99993 0.00340633 3.84535 +EDGE_SE3:QUAT 960 1203 3.71089 4.00286 0.00281538 -0.000893622 0.00738028 -0.973336 0.229263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.74581e-05 -0.00313315 3.99981 0.0272663 0.210447 +EDGE_SE3:QUAT 961 1203 0.842769 3.1611 -0.0320828 0.00599056 0.00316033 -0.999974 0.00242014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 7.38668e-05 0.0239624 4.00054 0.0125276 0.00020621 +EDGE_SE3:QUAT 962 1203 -1.8979 3.51817 -0.0105253 -0.00329931 -0.00451012 0.974234 0.225471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.85866e-05 0.0137516 3.99995 0.0214376 0.203517 +EDGE_SE3:QUAT 963 1203 -4.5857 4.93103 -0.0743912 -0.00969955 -0.00219773 0.914924 0.403503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000547095 0.0459132 4.00056 0.0316463 0.6521 +EDGE_SE3:QUAT 1062 1203 4.13245 -2.36991 -0.0479854 0.00170012 0.00759456 -0.417693 0.908555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -0.000467945 0.0531095 4.00001 -0.0104237 3.30282 +EDGE_SE3:QUAT 1063 1203 0.243496 -1.7523 -0.0145255 -0.00238401 0.00476853 -0.318776 0.947815 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -0.000113453 0.0239818 4 -0.00300888 3.59366 +EDGE_SE3:QUAT 1064 1203 -3.78095 -1.71243 -0.0292013 -0.00168864 0.00501049 -0.292586 0.956224 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -0.000136604 0.0294587 3.99998 -0.00375576 3.65778 +EDGE_SE3:QUAT 1123 1203 5.69434 -1.69749 -0.0265154 -0.00281737 0.00573604 -0.280417 0.959857 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -0.000168272 0.0316004 3.99998 -0.00372327 3.68571 +EDGE_SE3:QUAT 1124 1203 1.62456 -1.60575 -0.0138218 -0.00294597 0.00109388 -0.280015 0.959991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.9106e-06 -0.00163932 4 0.000740919 3.68636 +EDGE_SE3:QUAT 1125 1203 -2.74124 -1.4951 -0.0231955 -0.00460149 0.00231704 -0.276967 0.960866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.14774e-06 0.00193297 4 0.000540303 3.69315 +EDGE_SE3:QUAT 1126 1203 -7.0288 -1.41563 -0.00958774 -0.00584412 0.00513714 -0.275588 0.961244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -8.56365e-05 0.0181546 4.00001 -0.00139047 3.69627 +EDGE_SE3:QUAT 1204 1205 3.99831 -0.804339 0.000885154 0.000299579 0.00235711 -0.179345 0.983783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -2.09901e-05 0.0185857 3.99998 -0.0016581 3.87143 +EDGE_SE3:QUAT 959 1204 2.86055 3.22441 0.0189982 0.000873747 0.00725126 -0.977954 0.208692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.58291e-05 0.00424342 3.99993 0.0245006 0.174373 +EDGE_SE3:QUAT 960 1204 -0.267888 2.92487 0.0236556 -0.00588638 0.00935496 -0.999395 0.0329701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000220881 -0.0235843 4.00012 0.0388738 0.00486546 +EDGE_SE3:QUAT 961 1204 -3.21173 3.94719 -0.0529457 -0.00212506 -0.00752687 0.980835 0.194684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.71306e-05 0.00852535 3.99976 0.030476 0.151867 +EDGE_SE3:QUAT 1063 1204 2.96151 -4.83134 -0.0184814 -0.00740392 0.00232662 -0.499187 0.866459 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000100454 -0.0248748 3.9999 0.0104584 3.00337 +EDGE_SE3:QUAT 1064 1204 -0.889709 -4.65697 -0.0414084 -0.00665205 0.00265777 -0.475432 0.879724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 9.18854e-05 -0.0177552 3.99993 0.00781289 3.09591 +EDGE_SE3:QUAT 1065 1204 -4.99104 -4.54209 -0.0380723 -0.0081488 0.00272925 -0.47576 0.879533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000129092 -0.0246451 3.99989 0.0101357 3.09472 +EDGE_SE3:QUAT 1124 1204 4.59724 -4.46343 0.00528897 -0.00717556 -0.001621 -0.463604 0.886012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -7.38112e-05 -0.0432239 3.99989 0.0126446 3.14075 +EDGE_SE3:QUAT 1125 1204 0.245866 -4.32095 -0.00893148 -0.00901327 -0.000739438 -0.460849 0.887432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -8.51165e-06 -0.0469266 3.99984 0.0143725 3.15101 +EDGE_SE3:QUAT 1126 1204 -4.04893 -4.23569 -0.00224336 -0.0107521 0.00193476 -0.459343 0.888192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000170975 -0.0400838 3.9998 0.0140639 3.15637 +EDGE_SE3:QUAT 1205 1206 4.38347 -0.613 -0.116065 0.00701623 0.0393768 -0.0961338 0.994564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.02532 -0.00254075 0.320483 3.99384 -0.015452 3.98855 +EDGE_SE3:QUAT 959 1205 -1.0926 2.32224 0.0169258 0.00196785 0.00736113 -0.999522 0.0299769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.72691e-05 0.00788424 3.99987 0.0289069 0.00381912 +EDGE_SE3:QUAT 960 1205 -4.29189 3.46526 0.0896081 0.00515907 -0.00809538 0.989147 0.146615 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -9.04326e-05 -0.0214948 4.00046 0.024738 0.0862599 +EDGE_SE3:QUAT 1206 1207 4.04676 -0.168803 0.0285684 -0.00120734 0.00219946 -0.0156315 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.22131e-05 0.017363 3.99998 -0.000135242 3.9991 +EDGE_SE3:QUAT 959 1206 -5.49354 2.69421 -0.109149 -0.0406635 -0.00157317 0.996973 0.0662495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99369 0.00287092 0.163621 4.02602 0.0279828 0.0244815 +EDGE_SE3:QUAT 1207 1208 4.18907 -0.111741 0.037879 0.00173115 -0.00288407 -0.00219371 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.0357e-05 -0.0230274 3.99997 2.55877e-05 4.00011 +EDGE_SE3:QUAT 1208 1209 4.46853 -0.0880248 -0.00478441 9.23159e-05 -0.00702015 0.00367749 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 1.75683e-06 -0.0561738 3.9998 -0.000103235 4.00073 +EDGE_SE3:QUAT 955 1208 3.03694 1.6269 0.0655361 -0.00092599 -0.0079044 0.999929 0.00887916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.49835e-05 0.00370467 3.99976 0.0316763 0.00056967 +EDGE_SE3:QUAT 956 1208 -1.38624 1.75161 0.0682844 0.00223629 0.00816771 -0.999964 0.000609608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.33086e-05 0.00894603 3.99981 0.0326597 0.000288169 +EDGE_SE3:QUAT 957 1208 -5.61283 1.81754 0.0103171 0.00555631 0.00794383 -0.999946 0.0036854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.0001757 0.0222274 4.00025 0.0316149 0.000427696 +EDGE_SE3:QUAT 1209 1210 4.01508 -0.0696355 -0.0346413 0.00168774 0.00166847 0.00496172 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.14781e-05 0.0132468 3.99999 3.28923e-05 3.99995 +EDGE_SE3:QUAT 954 1209 2.94998 1.71002 0.0575454 0.00231659 -0.00961938 0.99989 0.0110588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -9.57112e-05 -0.00926945 3.99973 0.0382603 0.000876701 +EDGE_SE3:QUAT 955 1209 -1.40938 1.79121 0.0557244 0.005943 -0.00809738 0.999933 0.0057993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000190586 -0.023775 4.00032 0.0321164 0.000533687 +EDGE_SE3:QUAT 956 1209 -5.8092 1.82685 0.0573126 -0.00459729 0.00880541 -0.999941 0.00440086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000161398 -0.0183917 4.00002 0.0353844 0.000475043 +EDGE_SE3:QUAT 1210 1211 4.25828 -0.088548 0.018332 -0.00070361 0.00960917 -0.000304107 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00148 -2.77523e-05 0.0768956 3.99963 -1.32633e-05 4.00148 +EDGE_SE3:QUAT 953 1210 3.374 1.77801 0.0558222 -0.00214951 -0.00670001 0.999963 0.00494198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.63562e-05 0.0085989 3.99989 0.0268834 0.000296866 +EDGE_SE3:QUAT 954 1210 -1.05421 1.87142 0.0464254 0.000445802 -0.0081743 0.999947 0.00624514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.78734e-05 -0.00178353 3.99974 0.0326707 0.000423674 +EDGE_SE3:QUAT 955 1210 -5.41157 1.90786 0.0682644 0.00416735 -0.00688468 0.999967 0.000650017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000114755 -0.0166705 4.00009 0.027519 0.00026048 +EDGE_SE3:QUAT 1211 1212 4.39688 -0.101113 0.0494481 6.51681e-06 -0.00230313 -0.00141801 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -2.40563e-07 -0.0184252 3.99998 1.30651e-05 4.00008 +EDGE_SE3:QUAT 952 1211 3.3901 1.81519 0.106373 -0.00828246 -0.0079593 0.999925 0.00421009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.00026863 0.0331328 4.00083 0.0321257 0.0006033 +EDGE_SE3:QUAT 953 1211 -0.874428 1.91813 0.0621582 -0.0117012 -0.00742362 0.999889 0.00549844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99946 0.000363565 0.046808 4.00195 0.0302287 0.000897044 +EDGE_SE3:QUAT 954 1211 -5.26651 2.00977 0.0732207 -0.00899363 -0.00898806 0.999897 0.0066349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.000332013 0.0359801 4.00095 0.0364402 0.000831621 +EDGE_SE3:QUAT 1212 1213 4.33075 -0.086143 0.0209813 -0.00292538 -0.00106284 -0.000662291 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.24642e-05 -0.00852591 4 2.74625e-06 4.00002 +EDGE_SE3:QUAT 951 1212 2.97181 1.85883 0.0761365 0.00137975 -0.00727213 0.999961 0.00477145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.19177e-05 -0.00551965 3.99982 0.0290338 0.000309437 +EDGE_SE3:QUAT 952 1212 -0.988455 1.94224 0.0811499 -0.00590351 -0.00836281 0.99993 0.00594682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000199081 0.0236174 4.00026 0.0337343 0.000565386 +EDGE_SE3:QUAT 953 1212 -5.23639 2.06087 0.0120491 -0.00942086 -0.00740521 0.999902 0.00721573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000291338 0.0376881 4.00118 0.0301745 0.000790942 +EDGE_SE3:QUAT 1213 1214 4.03045 -0.108252 -5.31747e-05 0.00107488 0.000529525 0.0001951 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.27622e-06 0.00423368 4 4.20141e-07 4 +EDGE_SE3:QUAT 950 1213 3.05754 1.89711 0.0546413 0.000751876 -0.00928973 0.999946 0.00461849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.10503e-05 -0.00300802 3.99967 0.0371277 0.000432236 +EDGE_SE3:QUAT 951 1213 -1.33753 1.98779 0.106757 0.00243449 -0.0101044 0.999929 0.00586614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000102287 -0.00973998 3.99969 0.0402992 0.00056741 +EDGE_SE3:QUAT 952 1213 -5.30951 2.07636 0.0589787 -0.00497933 -0.0110825 0.999904 0.00660126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000218041 0.019922 3.99989 0.0445914 0.000770644 +EDGE_SE3:QUAT 1214 1215 4.43683 -0.0823942 0.0160123 0.00161961 0.00597531 0.00131444 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 3.98277e-05 0.0477826 3.99986 3.27967e-05 4.00056 +EDGE_SE3:QUAT 949 1214 3.26103 1.95362 0.071587 -0.00512072 -0.00893218 0.999942 0.00303558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000182939 0.0204854 4.00009 0.0358559 0.000463166 +EDGE_SE3:QUAT 950 1214 -0.986822 2.03782 0.0700297 0.000200174 -0.00808261 0.999959 0.00413807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.62757e-06 -0.000800818 3.99974 0.0323214 0.000329844 +EDGE_SE3:QUAT 951 1214 -5.35771 2.13391 0.13854 0.00172809 -0.00873782 0.999947 0.00521158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.31754e-05 -0.00691343 3.99975 0.0348762 0.000424704 +EDGE_SE3:QUAT 1215 1216 4.18643 -0.0768773 0.0649679 -0.00140614 0.00152155 0.00355626 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -8.41522e-06 0.0122322 3.99999 2.17077e-05 3.99999 +EDGE_SE3:QUAT 948 1215 3.17031 1.95733 0.0875403 -0.0112012 -0.00703631 0.999913 7.24801e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000315973 0.0448053 4.00181 0.0281705 0.000700218 +EDGE_SE3:QUAT 949 1215 -1.178 2.06434 0.0475864 -0.0112913 -0.00719168 0.999909 0.00146486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 0.000329225 0.0451661 4.00183 0.0289184 0.000727562 +EDGE_SE3:QUAT 950 1215 -5.39269 2.16705 0.0915402 -0.00571958 -0.00638106 0.999959 0.00289474 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000147353 0.0228797 4.00036 0.0256602 0.000328981 +EDGE_SE3:QUAT 1216 1217 4.06071 -0.0866488 0.0527406 0.00230676 -0.00446295 0.00267365 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -4.00219e-05 -0.0357795 3.99992 -4.67672e-05 4.00029 +EDGE_SE3:QUAT 947 1216 3.30629 1.96427 0.0929228 0.00773482 0.0101792 -0.999906 0.00496986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000312 0.0309442 4.00056 0.0404181 0.000746514 +EDGE_SE3:QUAT 948 1216 -0.981011 2.05097 0.0595486 0.0129439 0.00886014 -0.999872 0.00323536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 0.000448691 0.0517781 4.00239 0.0351357 0.00102058 +EDGE_SE3:QUAT 949 1216 -5.33354 2.15939 0.0259498 0.012814 0.00909085 -0.999875 0.00203244 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 0.000460259 0.0512582 4.00231 0.0361859 0.00100055 +EDGE_SE3:QUAT 1217 1218 4.17613 -0.0709823 2.46377e-05 -0.00295804 -0.00460193 0.000989869 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 5.4899e-05 -0.0367825 3.99992 -1.97045e-05 4.00033 +EDGE_SE3:QUAT 946 1217 3.43715 1.9332 0.0532992 -0.00341659 0.00702015 -0.999916 0.0103622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.45989e-05 -0.0136694 3.99998 0.0283573 0.000677274 +EDGE_SE3:QUAT 947 1217 -0.735199 1.99589 0.0851763 0.0033096 0.00796498 -0.999933 0.00778273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000107249 0.0132408 3.99993 0.03165 0.000536562 +EDGE_SE3:QUAT 948 1217 -5.02749 2.10924 0.0162559 0.00851695 0.00679133 -0.999918 0.00668855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.00022224 0.034071 4.00099 0.0267167 0.000647575 +EDGE_SE3:QUAT 1218 1219 4.07044 -0.118395 0.00384498 0.00146921 0.0065983 -0.0133699 0.999888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 2.49522e-05 0.053016 3.99982 -0.000353519 3.99999 +EDGE_SE3:QUAT 945 1218 3.28924 1.83323 0.0654605 0.000593339 0.0109386 -0.999797 0.016893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.18429e-05 0.00237539 3.99953 0.0436406 0.00161922 +EDGE_SE3:QUAT 946 1218 -0.747822 1.91168 0.0919822 -0.00814607 0.0100589 -0.999848 0.0116786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000336419 -0.0325951 4.00061 0.0409954 0.00123131 +EDGE_SE3:QUAT 947 1218 -4.863 2.00485 0.0630364 -0.00085969 0.0113822 -0.999888 0.00966201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.92344e-05 -0.00343972 3.99949 0.0455817 0.000895912 +EDGE_SE3:QUAT 1219 1220 4.12446 -0.291431 0.0379514 0.00224657 -0.0201274 -0.0788178 0.996683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00618 -0.000919879 -0.157614 3.99852 0.00621077 3.98135 +EDGE_SE3:QUAT 944 1219 3.6516 1.81628 0.0804641 0.0100124 0.00875596 -0.999484 0.0292464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 0.000293949 0.0401037 4.00142 0.032626 0.00409011 +EDGE_SE3:QUAT 945 1219 -0.748869 1.79782 0.0669941 0.00695796 0.00977108 -0.999922 0.00345423 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000270655 0.0278356 4.0004 0.0388995 0.000619666 +EDGE_SE3:QUAT 946 1219 -4.79427 1.92713 0.159155 0.00148548 -0.00876454 0.999959 0.0016944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.30209e-05 -0.00594262 3.99973 0.0350369 0.000327228 +EDGE_SE3:QUAT 1220 1221 4.14758 -0.717442 0.00439689 0.000670905 0.00215106 -0.168549 0.985691 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.39972e-05 0.017812 3.99998 -0.00151816 3.88644 +EDGE_SE3:QUAT 943 1220 3.33306 2.08863 0.0202822 0.000847727 0.00833585 -0.999098 0.0416227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.97222e-05 0.00340503 3.99975 0.0329164 0.00720408 +EDGE_SE3:QUAT 944 1220 -0.480546 1.88378 0.0390335 0.0109224 -0.00661028 0.998674 0.0498697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99947 -0.000152868 -0.0438568 4.0019 0.0219443 0.0105508 +EDGE_SE3:QUAT 945 1220 -4.87913 2.07426 0.0617558 0.0135982 -0.00823981 0.997039 0.0752377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99916 -0.00011818 -0.0548752 4.00305 0.0243794 0.02355 +EDGE_SE3:QUAT 1221 1222 3.93188 -0.763247 -0.00145198 0.000263118 -0.00206398 -0.179295 0.983793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.82672e-05 -0.0151682 3.99999 0.0013186 3.87147 +EDGE_SE3:QUAT 941 1221 5.40572 4.3237 0.0466614 0.0051299 0.00882636 -0.9583 0.285581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -7.49694e-05 0.0245149 4.00073 0.0175557 0.326488 +EDGE_SE3:QUAT 942 1221 2.53076 2.75922 -0.00742442 0.000760543 0.0043032 -0.997533 0.0700577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.12537e-05 0.00307643 3.99995 0.0165777 0.0197038 +EDGE_SE3:QUAT 943 1221 -0.855032 2.46922 0.0300406 -0.00156004 -0.00767339 0.991774 0.127758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.29717e-05 0.00626313 3.99976 0.0310157 0.0655426 +EDGE_SE3:QUAT 944 1221 -4.52413 3.00384 0.151406 0.00957246 -0.00401464 0.976114 0.217013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000371142 -0.0412241 4.00159 -0.00164056 0.188824 +EDGE_SE3:QUAT 1222 1223 4.0147 -0.79794 0.00817771 0.00626466 0.00424826 -0.169876 0.985436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 3.55289e-05 0.045054 3.99986 -0.00414235 3.88507 +EDGE_SE3:QUAT 940 1222 4.59399 3.81706 0.00786607 0.00199196 0.00547473 -0.957897 0.287052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.17526e-05 0.00992605 4.00013 0.0133235 0.329675 +EDGE_SE3:QUAT 941 1222 1.7169 2.78569 -0.000662953 0.00161649 0.00863915 -0.993949 0.109489 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000100424 0.00667279 3.99984 0.0321266 0.0482239 +EDGE_SE3:QUAT 942 1222 -1.45028 2.96191 -0.00991066 0.00173406 -0.0039985 0.99394 0.109841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.79848e-05 -0.0071031 4.00002 0.0140085 0.0483231 +EDGE_SE3:QUAT 943 1222 -4.46588 4.16823 0.0413032 0.00158527 -0.00799338 0.952909 0.303147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -6.11219e-05 -0.00893469 4.0001 0.0213789 0.367752 +EDGE_SE3:QUAT 1223 1224 4.28332 -0.590191 -0.0104682 -0.00162175 -0.00108102 -0.110823 0.993838 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.81671e-06 -0.0106284 3.99999 0.000625742 3.9509 +EDGE_SE3:QUAT 939 1223 4.29654 3.0031 -0.00453507 -0.00166322 0.00313434 -0.957055 0.289885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.94851e-06 -0.00682655 3.99996 0.0135153 0.336196 +EDGE_SE3:QUAT 940 1223 0.824271 2.28531 -0.00785147 0.00695217 0.0010979 -0.992769 0.119836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000110679 0.0284158 4.00078 -0.00233568 0.0576492 +EDGE_SE3:QUAT 941 1223 -2.35917 2.68009 -0.00209792 -0.00521766 -0.00305965 0.9981 0.0613098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 9.53225e-05 0.0209827 4.00035 0.0146753 0.0152 +EDGE_SE3:QUAT 942 1223 -5.18144 4.5928 0.0271137 -0.00131807 0.00292158 0.960872 0.276975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.82871e-07 0.00633988 4.00005 -0.00680983 0.306886 +EDGE_SE3:QUAT 1224 1225 4.09698 -0.272728 0.0109815 -0.000236837 0.000192393 -0.0328464 0.99946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.93574e-07 0.00144337 4 -2.31803e-05 3.99568 +EDGE_SE3:QUAT 938 1224 4.03842 1.75958 0.00426674 -0.000906863 0.00694754 -0.937717 0.347331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.72606e-05 -0.00189306 3.9999 0.021988 0.482699 +EDGE_SE3:QUAT 939 1224 0.408319 1.11429 -0.00392961 -0.00331902 0.0040779 -0.983243 0.182223 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.09333e-05 -0.0137238 4 0.0196515 0.132969 +EDGE_SE3:QUAT 940 1224 -3.47465 1.83065 -0.0784999 0.00567086 0.00341305 -0.999937 0.00910517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 7.11716e-05 0.0226863 4.00048 0.0132386 0.000504109 +EDGE_SE3:QUAT 1225 1226 4.36277 -0.126191 0.0209198 -0.000631615 0.000332429 -0.0131754 0.999913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.30454e-07 0.00255889 4 -1.6638e-05 3.99931 +EDGE_SE3:QUAT 937 1225 5.14452 0.974128 0.00787545 -0.00127176 0.00556629 -0.815855 0.578229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.2915e-05 0.00168334 4.00001 0.0099342 1.33746 +EDGE_SE3:QUAT 938 1225 0.771005 -0.701014 0.0106823 -0.00101362 0.00698698 -0.948573 0.31648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.63818e-05 -0.00284429 3.99987 0.0235095 0.400799 +EDGE_SE3:QUAT 939 1225 -3.51688 -0.0924972 0.0308274 -0.00341001 0.0040328 -0.988697 0.149835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.82554e-05 -0.0139836 4.00003 0.0192292 0.0899464 +EDGE_SE3:QUAT 1226 1227 3.99601 -0.244199 0.0201055 0.00118868 -0.00192429 -0.0541365 0.998531 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.29035e-05 -0.0145561 3.99999 0.000386541 3.98833 +EDGE_SE3:QUAT 937 1226 3.56391 -3.11844 0.0159283 -0.00148098 0.00630774 -0.823496 0.567286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 3.63645e-05 0.00119405 4.00001 0.0119629 1.28734 +EDGE_SE3:QUAT 938 1226 -2.80446 -3.21987 0.0216331 -0.000983799 0.00764669 -0.952653 0.303961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.97817e-05 -0.00272326 3.99984 0.0259258 0.36976 +EDGE_SE3:QUAT 1227 1228 4.10491 -0.493713 0.00705586 -0.000298434 0.013314 -0.122495 0.99238 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00269 -0.000519366 0.10375 3.99938 -0.00630886 3.94267 +EDGE_SE3:QUAT 937 1227 1.91796 -6.75315 0.0191988 -0.00299761 0.00417567 -0.852715 0.522352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.20808e-05 -0.0110429 3.99992 0.0155786 1.09152 +EDGE_SE3:QUAT 1228 1229 3.91867 -0.605625 0.0140486 -0.00190942 0.00270695 -0.151872 0.988395 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -3.48347e-05 0.0174845 3.99999 -0.00122067 3.90782 +EDGE_SE3:QUAT 1229 1230 4.1962 -0.781357 0.0210853 0.000902983 -0.00165642 -0.178191 0.983994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.30987e-05 -0.0107353 3.99999 0.000880027 3.87302 +EDGE_SE3:QUAT 298 1229 3.62766 -4.66082 0.0540011 -0.0137078 -0.00407107 0.702272 0.711765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 0.000129689 0.0658021 3.99961 0.0383455 2.0283 +EDGE_SE3:QUAT 299 1229 -2.72528 -4.79571 0.0391088 -0.0101468 0.00223146 0.5212 0.853372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 0.000261732 0.063079 3.99982 0.0209423 2.91439 +EDGE_SE3:QUAT 1230 1231 4.04563 -0.695669 0.00909816 0.00344374 -0.00494473 -0.145818 0.989293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -0.000115179 -0.0323632 3.99995 0.00218398 3.91521 +EDGE_SE3:QUAT 298 1230 4.47702 -0.454809 0.0344595 -0.0110279 -0.00704188 0.564054 0.825634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 -0.000324853 0.0270973 3.99976 0.0174015 2.72741 +EDGE_SE3:QUAT 299 1230 -0.116648 -1.43458 0.0156841 -0.00881817 -0.000372797 0.360889 0.932567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000110061 0.0324541 3.99989 0.00816902 3.47928 +EDGE_SE3:QUAT 300 1230 -4.56397 -0.9112 -0.0198935 -0.00839259 -0.00159007 0.256998 0.966374 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -8.85395e-05 0.0132617 3.99997 0.00286682 3.73583 +EDGE_SE3:QUAT 1231 1232 4.17224 -0.543958 -0.0730698 0.00278445 0.0197861 -0.100023 0.994785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00632 -0.000731831 0.159461 3.99847 -0.0079975 3.96633 +EDGE_SE3:QUAT 298 1231 6.56397 3.04215 0.0678757 -0.00435378 -0.0107219 0.437708 0.899043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 0.0005185 -0.0423914 4.00014 -0.00558783 3.234 +EDGE_SE3:QUAT 299 1231 3.33977 0.760827 0.0145909 -0.00369438 -0.00529439 0.221185 0.975211 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 0.000136708 -0.0297993 3.99997 -0.00281786 3.80453 +EDGE_SE3:QUAT 300 1231 -0.721445 0.503532 -0.00145723 -0.00368489 -0.00670047 0.11323 0.993539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 0.000186375 -0.0476163 3.99988 -0.00258611 3.94928 +EDGE_SE3:QUAT 301 1231 -4.77121 0.598596 -0.048555 -0.00024379 -0.0171599 0.100548 0.994784 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00455 0.000712485 -0.135043 3.99892 -0.00677158 3.96411 +EDGE_SE3:QUAT 1232 1233 4.06971 -0.254054 0.0131586 -0.00377122 -0.000438454 -0.0363515 0.999332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.04182e-05 -0.00514422 4 0.000103392 3.99472 +EDGE_SE3:QUAT 300 1232 3.47193 0.927567 -0.0161276 -0.00244309 0.0129489 0.0130469 0.999828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00268 -7.45886e-05 0.104008 3.99932 0.00067057 4.00202 +EDGE_SE3:QUAT 301 1232 -0.574991 0.912082 0.0283217 0.00229669 0.00302343 0.000398409 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 2.78493e-05 0.024177 3.99996 5.31941e-06 4.00015 +EDGE_SE3:QUAT 302 1232 -5.05292 0.903923 0.0419166 0.00209281 0.00372959 0.016896 0.999848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 3.61309e-05 0.0294009 3.99995 0.000247866 3.99907 +EDGE_SE3:QUAT 1233 1234 4.13991 -0.162665 0.0213623 0.0029158 -0.00489452 -0.0167388 0.999844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -6.53303e-05 -0.0385567 3.99991 0.000322732 3.99925 +EDGE_SE3:QUAT 301 1233 3.47257 0.660489 0.0149675 -0.00167128 0.0024675 -0.0360824 0.999344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -2.06121e-05 0.0189787 3.99998 -0.000338065 3.99488 +EDGE_SE3:QUAT 302 1233 -0.987291 0.794189 0.0264404 -0.00202413 0.00325938 -0.0196613 0.999799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.05964e-05 0.0255833 3.99996 -0.000250414 3.99862 +EDGE_SE3:QUAT 303 1233 -5.09782 0.787934 0.0364512 -0.00138234 0.00649092 -0.00426934 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 -4.01536e-05 0.0518626 3.99983 -0.000112102 4.0006 +EDGE_SE3:QUAT 1234 1235 4.34762 -0.120675 0.0336497 -4.37966e-05 -0.00871914 -0.00618674 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 -9.76317e-06 -0.0697709 3.9997 0.000215919 4.00106 +EDGE_SE3:QUAT 302 1234 3.13456 0.444781 0.0206286 0.000633544 -0.001892 -0.0359631 0.999351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -7.66339e-06 -0.0148337 3.99999 0.00026498 3.99488 +EDGE_SE3:QUAT 303 1234 -0.970376 0.572468 0.00777516 0.00113634 0.00132936 -0.0208646 0.999781 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 5.33134e-06 0.0109124 3.99999 -0.000114758 3.99829 +EDGE_SE3:QUAT 304 1234 -5.21225 0.604924 -0.000422741 -0.00160817 0.00518469 -0.00795252 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -3.82959e-05 0.0413238 3.99989 -0.000165183 4.00017 +EDGE_SE3:QUAT 1235 1236 4.33421 -0.101638 -0.0221362 0.00239534 0.00287819 -2.18399e-05 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 2.75765e-05 0.0230266 3.99997 2.2479e-07 4.00013 +EDGE_SE3:QUAT 302 1235 7.42094 0.0146879 0.0696555 0.000309751 -0.0102409 -0.0421161 0.99906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00166 -0.00011803 -0.0815822 3.99959 0.00171799 3.99457 +EDGE_SE3:QUAT 303 1235 3.35431 0.267409 0.0273866 0.000691153 -0.00720643 -0.0269954 0.999609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 -5.32122e-05 -0.0573749 3.9998 0.000774413 3.99791 +EDGE_SE3:QUAT 304 1235 -0.85909 0.397143 -0.00672545 -0.00196234 -0.00364869 -0.0139347 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 2.45341e-05 -0.0295103 3.99995 0.000205742 3.99944 +EDGE_SE3:QUAT 305 1235 -5.07183 0.473851 0.0149781 -0.00125682 -0.00162579 -0.0105953 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 7.62072e-06 -0.013164 3.99999 6.99368e-05 3.99959 +EDGE_SE3:QUAT 1236 1237 4.39458 -0.101868 0.00200279 0.00176007 0.00459084 0.00176385 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 3.31771e-05 0.0366918 3.99992 3.32445e-05 4.00032 +EDGE_SE3:QUAT 304 1236 3.44779 0.186147 0.00317008 0.000292866 -0.000796482 -0.0143071 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.13794e-06 -0.00631964 4 4.50879e-05 3.99919 +EDGE_SE3:QUAT 305 1236 -0.753769 0.284566 0.0125801 0.0010381 0.00135498 -0.0108462 0.99994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 5.2316e-06 0.0109731 3.99999 -5.97036e-05 3.99956 +EDGE_SE3:QUAT 306 1236 -5.06677 0.378814 -0.0166649 -0.00231317 -0.00254149 -0.00977875 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.23843e-05 -0.0206007 3.99997 0.000100803 3.99972 +EDGE_SE3:QUAT 1237 1238 4.36537 -0.0749585 0.0334369 -0.000498591 0.00973279 0.0017546 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00152 -1.54482e-05 0.0778982 3.99962 6.72768e-05 4.0015 +EDGE_SE3:QUAT 305 1237 3.62689 0.0918877 0.00325318 0.00284457 0.00593823 -0.00939234 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00054 6.01633e-05 0.0478256 3.99986 -0.000222739 4.00022 +EDGE_SE3:QUAT 306 1237 -0.676716 0.197736 0.0154189 -0.000424211 0.00208199 -0.00805453 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -4.35562e-06 0.0166136 3.99998 -6.6897e-05 3.99981 +EDGE_SE3:QUAT 307 1237 -4.98299 0.281823 -0.13332 0.00108437 -0.00992637 -0.00764424 0.999921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 -6.10859e-05 -0.0793317 3.99961 0.000305953 4.00134 +EDGE_SE3:QUAT 1238 1239 4.01047 -0.0832888 0.0278924 -0.00238523 -0.00354607 0.00214812 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 3.43864e-05 -0.0283079 3.99995 -3.11037e-05 4.00018 +EDGE_SE3:QUAT 306 1238 3.6969 0.0502191 0.0323766 -0.00105788 0.0116832 -0.00630371 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00218 -7.01066e-05 0.0934243 3.99946 -0.000298254 4.00202 +EDGE_SE3:QUAT 307 1238 -0.607058 0.128892 -0.00408112 0.00040811 -0.000218439 -0.00576643 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.5532e-07 -0.00171919 4 4.93001e-06 3.99987 +EDGE_SE3:QUAT 308 1238 -4.94104 0.223551 -0.0549936 0.00398645 -0.000843899 -0.00551845 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.28426e-05 -0.00648675 4 1.77193e-05 3.99989 +EDGE_SE3:QUAT 1239 1240 4.38825 -0.0768462 -0.00850983 -0.00348524 -0.00190626 0.00280704 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.65444e-05 -0.0151324 3.99999 -2.14846e-05 4.00003 +EDGE_SE3:QUAT 307 1239 3.38881 0.0190673 0.0252429 -0.00190671 -0.00385076 -0.00380565 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 2.81245e-05 -0.0308939 3.99994 5.8168e-05 4.00018 +EDGE_SE3:QUAT 308 1239 -0.937206 0.0965132 -0.0145724 0.00137449 -0.00435306 -0.00334843 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -2.54071e-05 -0.0347708 3.99992 5.88178e-05 4.00026 +EDGE_SE3:QUAT 309 1239 -5.27239 0.194696 0.00513082 0.00332883 0.000196753 -0.00339411 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.917e-06 0.00170955 4 -2.97435e-06 3.99995 +EDGE_SE3:QUAT 1240 1241 4.39317 -0.0782749 0.00117039 -0.000137438 0.00280211 0.003612 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -8.60186e-07 0.022423 3.99997 4.04768e-05 4.00007 +EDGE_SE3:QUAT 308 1240 3.44975 -0.0120601 0.0171999 -0.00222923 -0.00614213 -0.000492225 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 5.43708e-05 -0.0491563 3.99985 1.00842e-05 4.0006 +EDGE_SE3:QUAT 309 1240 -0.888799 0.0862435 -0.000971144 -0.000286315 -0.00152706 -0.000576665 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.71703e-06 -0.0122186 3.99999 3.50725e-06 4.00004 +EDGE_SE3:QUAT 310 1240 -5.32893 0.165892 0.0143379 0.000920137 -0.000474465 -0.000490558 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.74561e-06 -0.0037903 4 9.34199e-07 4 +EDGE_SE3:QUAT 1241 1242 4.29742 -0.0812807 0.0350216 -2.39898e-06 -0.00157653 0.001041 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 7.72256e-08 -0.0126123 3.99999 -6.56503e-06 4.00004 +EDGE_SE3:QUAT 309 1241 3.49233 0.00680438 0.00555718 -0.000456687 0.00125127 0.00284436 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.18337e-06 0.0100257 3.99999 1.42487e-05 3.99999 +EDGE_SE3:QUAT 310 1241 -0.940028 0.0943873 0.0217563 0.000531555 0.00259396 0.00323319 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 6.02976e-06 0.0207312 3.99997 3.35908e-05 4.00007 +EDGE_SE3:QUAT 311 1241 -5.16295 0.198978 0.00333553 -0.000453287 0.0036231 0.0039281 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -5.33769e-06 0.0290069 3.99995 5.68494e-05 4.00015 +EDGE_SE3:QUAT 1242 1243 4.41356 -0.10973 0.0494247 0.00130954 -0.00279041 -0.00491362 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -1.54633e-05 -0.0222458 3.99997 5.48376e-05 4.00003 +EDGE_SE3:QUAT 310 1242 3.34706 0.0371117 0.03013 0.000829639 0.00110724 0.00460395 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.78337e-06 0.00881184 4 2.02737e-05 3.99993 +EDGE_SE3:QUAT 311 1242 -0.877948 0.139121 0.00801981 -0.000341058 0.00215083 0.00536632 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -2.34228e-06 0.0172281 3.99998 4.62091e-05 3.99996 +EDGE_SE3:QUAT 312 1242 -5.07574 0.22769 -0.0519265 -0.000962894 0.000981281 0.00619315 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.68002e-06 0.00792137 4 2.45802e-05 3.99986 +EDGE_SE3:QUAT 1243 1244 4.21939 -0.133589 0.0256481 -0.000235212 -0.00729081 -0.00989811 0.999924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00085 -5.77016e-06 -0.0583567 3.99979 0.000288704 4.00046 +EDGE_SE3:QUAT 311 1243 3.53803 0.0762828 0.0363643 0.00090294 -0.000580999 0.000189638 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.09813e-06 -0.00465005 4 -4.33657e-07 4.00001 +EDGE_SE3:QUAT 312 1243 -0.651019 0.170898 -0.00893512 0.000303229 -0.00181354 0.00129434 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -2.09849e-06 -0.0145131 3.99999 -9.36984e-06 4.00005 +EDGE_SE3:QUAT 313 1243 -4.7964 0.234541 0.00173069 -0.00136401 0.00462712 0.00355405 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -2.34747e-05 0.0370771 3.99991 6.52332e-05 4.00029 +EDGE_SE3:QUAT 1244 1245 4.18351 -0.165785 -0.00227905 0.00176286 -0.00126338 -0.02435 0.999701 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -9.15232e-06 -0.00958316 3.99999 0.000114612 3.99765 +EDGE_SE3:QUAT 312 1244 3.55302 0.0478986 0.0352311 -0.000108387 -0.00904988 -0.00851283 0.999923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00131 -1.2813e-05 -0.072423 3.99967 0.000308319 4.00102 +EDGE_SE3:QUAT 313 1244 -0.574973 0.144295 -0.00404447 -0.00166146 -0.0025674 -0.00585648 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.62575e-05 -0.0206553 3.99997 6.03356e-05 3.99997 +EDGE_SE3:QUAT 314 1244 -4.64969 0.0986302 0.00174633 -0.0015008 0.000508271 0.0119308 0.999928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.18521e-06 0.00428014 4 2.59483e-05 3.99944 +EDGE_SE3:QUAT 1245 1246 4.22228 -0.28535 -0.0135961 -0.00467568 0.0227838 -0.0737539 0.997005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00772 -0.00129124 0.176951 3.99814 -0.00654635 3.98605 +EDGE_SE3:QUAT 313 1245 3.59288 -0.0581483 0.0116333 0.00027557 -0.0038759 -0.0303429 0.999532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -1.51142e-05 -0.0308657 3.99994 0.000467725 3.99656 +EDGE_SE3:QUAT 314 1245 -0.467032 0.0338509 0.00325977 0.000274972 -0.000485385 -0.0121988 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.94184e-07 -0.00384197 4 2.33517e-05 3.99941 +EDGE_SE3:QUAT 315 1245 -4.65168 -0.456411 -0.146545 0.00659222 -0.0203235 0.0772079 0.996786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00683 0.00024414 -0.167472 3.99826 -0.00648536 3.98315 +EDGE_SE3:QUAT 1246 1247 4.0228 -0.605478 0.0246658 0.00100961 0.000427022 -0.150432 0.98862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.58599e-06 0.00509591 4 -0.000426012 3.90949 +EDGE_SE3:QUAT 314 1246 3.76118 -0.348887 -0.0056122 -0.00405022 0.0223669 -0.0857755 0.996055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00741 -0.00132965 0.173086 3.99824 -0.0074193 3.97804 +EDGE_SE3:QUAT 315 1246 -0.450916 -0.0811379 0.0156137 0.00142153 0.00251281 0.00367786 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.47841e-05 0.0200397 3.99997 3.70297e-05 4.00005 +EDGE_SE3:QUAT 316 1246 -4.54153 -0.877939 -0.0210546 -0.000583256 0.000389695 0.160653 0.987011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.72371e-07 0.00410273 4 0.000356356 3.89677 +EDGE_SE3:QUAT 1247 1248 4.22082 -0.925436 0.0182567 0.00505598 -0.00583646 -0.205189 0.978692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -0.000162697 -0.0316735 3.99997 0.00272319 3.83183 +EDGE_SE3:QUAT 271 1247 -1.48883 7.31104 -0.0251178 0.000979546 0.00948189 -0.858612 0.512538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000100605 0.0153436 4.00033 0.0124955 1.05097 +EDGE_SE3:QUAT 315 1247 3.57552 -0.648453 0.0136093 0.00201393 0.00346382 -0.146828 0.989154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -1.78241e-05 0.0303182 3.99994 -0.00228994 3.914 +EDGE_SE3:QUAT 316 1247 -0.535014 -0.178962 0.00279739 0.000419388 0.000992075 0.0107705 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.9004e-06 0.00788104 4 4.23519e-05 3.99955 +EDGE_SE3:QUAT 317 1247 -4.48142 -1.0264 0.0150089 -0.00375612 0.00500607 0.185653 0.982595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00048 5.17468e-05 0.0461768 3.99987 0.00447798 3.86266 +EDGE_SE3:QUAT 1248 1249 4.01439 -0.829551 -0.00593072 0.00129927 0.00655299 -0.185172 0.982683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -0.000160851 0.0525799 3.99985 -0.00487277 3.86354 +EDGE_SE3:QUAT 269 1248 4.01497 3.83352 0.00933374 0.00142572 0.00308832 -0.9476 0.319442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.29615e-06 0.00731223 4.00007 0.00604545 0.408199 +EDGE_SE3:QUAT 270 1248 -0.254235 3.94695 -0.0209427 -0.00200072 0.00331076 -0.946429 0.322889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.44e-06 -0.00826199 3.99995 0.0145494 0.417106 +EDGE_SE3:QUAT 271 1248 -4.31564 4.03432 -0.0402614 -0.0035016 0.00230095 -0.945517 0.325547 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.36409e-05 -0.0154158 4.00003 0.0150111 0.424046 +EDGE_SE3:QUAT 316 1248 3.71376 -1.01615 0.010536 0.00504736 -0.00476396 -0.194956 0.980787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -0.000105746 -0.0244496 3.99998 0.00192902 3.84811 +EDGE_SE3:QUAT 317 1248 -0.237066 -0.318989 -0.00607211 0.00115964 -0.000591082 -0.0199538 0.9998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.67722e-06 -0.00444823 4 4.34558e-05 3.99841 +EDGE_SE3:QUAT 318 1248 -3.93239 -1.26993 -0.0699165 0.00124213 -0.0076381 0.194505 0.980871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00091 0.000235865 -0.0605085 3.99981 -0.00586487 3.84959 +EDGE_SE3:QUAT 1249 1250 4.15409 -0.620166 -0.0260729 0.00271131 0.00519733 -0.11002 0.993912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -1.8033e-05 0.0443813 3.99988 -0.00249187 3.95207 +EDGE_SE3:QUAT 268 1249 4.51886 1.94449 -0.0166831 -0.00580242 0.00876761 -0.990905 0.134155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000174922 -0.0236616 3.99993 0.0396199 0.0725304 +EDGE_SE3:QUAT 269 1249 0.327533 2.07122 -0.0101893 0.00743604 0.004379 -0.990341 0.138387 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -6.66599e-05 0.0306777 4.00098 0.0086104 0.0768633 +EDGE_SE3:QUAT 270 1249 -3.90254 2.15167 -0.00898782 0.00415646 0.00352611 -0.989868 0.141887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -3.69334e-06 0.0172006 4.00031 0.00877742 0.0806235 +EDGE_SE3:QUAT 317 1249 3.75104 -1.32476 -0.0134965 0.00247947 0.00605357 -0.205011 0.978738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 -0.00013702 0.0513441 3.99986 -0.00536348 3.83254 +EDGE_SE3:QUAT 318 1249 0.0890517 -0.512097 -0.010177 0.00251655 -0.000688775 0.00914788 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.28317e-06 -0.0057857 4 -2.68527e-05 3.99967 +EDGE_SE3:QUAT 319 1249 -3.71317 -1.52687 -0.0555969 0.000274947 -0.00860898 0.281586 0.959497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 0.000431398 -0.0617371 3.99987 -0.00833407 3.68378 +EDGE_SE3:QUAT 1250 1251 4.0311 -0.26273 0.00626284 0.000318169 0.00330248 -0.0338787 0.99942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -4.69584e-06 0.0265046 3.99996 -0.000449413 3.99558 +EDGE_SE3:QUAT 267 1250 4.57824 1.32814 0.0138677 0.00124641 0.00224416 -0.999768 0.0214025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.117e-05 0.00498926 4.00001 0.00875312 0.00185766 +EDGE_SE3:QUAT 268 1250 0.388487 1.41808 0.00852292 -0.00115958 0.00575799 -0.999677 0.0247375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.06988e-05 -0.00464207 3.99988 0.0232258 0.00258811 +EDGE_SE3:QUAT 269 1250 -3.81857 1.51989 -0.0965254 0.012506 0.00282559 -0.999503 0.028801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99936 3.35946e-05 0.0500826 4.00251 0.00840648 0.00396335 +EDGE_SE3:QUAT 318 1250 4.25055 -1.04821 -0.0328415 0.00536893 0.00484855 -0.100601 0.994901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 5.39092e-05 0.0446423 3.99987 -0.00234109 3.96002 +EDGE_SE3:QUAT 319 1250 0.113156 0.20249 0.000217391 0.0026311 -0.00281727 0.174537 0.984643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 7.40779e-06 -0.0269159 3.99995 -0.00247806 3.87833 +EDGE_SE3:QUAT 320 1250 -4.12122 -0.848624 -0.0219088 0.00336867 -0.00702575 0.423926 0.905663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 0.000464766 -0.0568512 3.99997 -0.0120236 3.28195 +EDGE_SE3:QUAT 1251 1252 4.15123 -0.114171 0.0248869 0.00166388 -0.00225969 -0.0023717 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.52772e-05 -0.0180303 3.99998 2.15666e-05 4.00006 +EDGE_SE3:QUAT 266 1251 4.65659 1.3859 0.0356548 -0.00640447 -0.00220135 0.999963 0.00536189 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 6.14707e-05 0.0256187 4.00063 0.0090815 0.000299704 +EDGE_SE3:QUAT 267 1251 0.559371 1.41805 0.0089041 -0.00438995 -0.00227587 0.999911 0.0124257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.51066e-05 0.0175638 4.00028 0.00953726 0.000717467 +EDGE_SE3:QUAT 268 1251 -3.64827 1.48075 0.0230234 -0.00188753 -0.00571248 0.99994 0.00913552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.14685e-05 0.00755139 3.99992 0.0229831 0.000480157 +EDGE_SE3:QUAT 319 1251 3.97145 1.32346 0.0337345 0.00241247 0.000660193 0.141049 0.989999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.7913e-07 0.00109552 4 -2.24696e-05 3.92042 +EDGE_SE3:QUAT 320 1251 -1.32654 2.07559 0.0469209 0.0022692 -0.00372411 0.392726 0.919645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 0.00012655 -0.0327698 3.99997 -0.00662126 3.38333 +EDGE_SE3:QUAT 321 1251 -6.10068 0.52496 0.0751133 0.00501325 -0.00221341 0.579608 0.814877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 0.000177355 -0.0366443 4 -0.012664 2.65655 +EDGE_SE3:QUAT 1252 1253 4.2569 -0.0881383 0.0151824 0.000775765 -0.000382424 0.00164596 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.18878e-06 -0.0030747 4 -2.53188e-06 3.99999 +EDGE_SE3:QUAT 265 1252 4.77764 1.5059 0.0260807 0.00441121 0.00246512 -0.999983 0.00304212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.22287e-05 0.017645 4.00029 0.00975392 0.000138639 +EDGE_SE3:QUAT 266 1252 0.517815 1.54509 0.00547179 -0.00413243 -0.000447008 0.999963 0.00747422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.04354e-05 0.016531 4.00027 0.00203506 0.000292814 +EDGE_SE3:QUAT 267 1252 -3.57033 1.6557 -0.00315797 -0.00206132 -0.00053732 0.999893 0.0144946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.85986e-06 0.00824787 4.00007 0.00238718 0.000858812 +EDGE_SE3:QUAT 320 1252 1.60097 4.98919 0.107503 0.00496541 -0.00526255 0.391024 0.920352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 0.000274965 -0.0537567 3.9999 -0.0113056 3.38912 +EDGE_SE3:QUAT 321 1252 -4.63373 4.38074 0.138561 0.00767277 -0.00316851 0.577976 0.816011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 0.000386627 -0.0551499 3.99999 -0.0191668 2.66453 +EDGE_SE3:QUAT 811 1252 5.94645 3.52329 0.152855 0.0107162 0.0022022 -0.549859 0.835186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -0.000344399 0.0667386 3.99983 -0.0235639 2.79173 +EDGE_SE3:QUAT 812 1252 -0.413312 4.78343 0.111667 0.00607296 0.00604821 -0.344802 0.938636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00085 -0.000288343 0.0631685 3.99982 -0.0117804 3.52544 +EDGE_SE3:QUAT 813 1252 -6.65557 2.96204 0.0639939 0.00640455 0.0034962 -0.101967 0.994761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 7.73969e-05 0.0353177 3.99991 -0.00192387 3.95872 +EDGE_SE3:QUAT 1253 1254 4.11135 -0.0829875 0.0158614 0.000818386 -0.00125115 0.00215887 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.02592e-06 -0.0100303 3.99999 -1.0804e-05 4.00001 +EDGE_SE3:QUAT 264 1253 4.77461 1.50052 0.0372057 0.00561342 0.00384006 -0.99987 0.0146068 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 7.6644e-05 0.022461 4.00046 0.0146987 0.0010336 +EDGE_SE3:QUAT 265 1253 0.534502 1.55462 0.00962314 0.00395802 0.00161388 -0.99998 0.00469259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 2.38809e-05 0.0158325 4.00024 0.00630711 0.000160696 +EDGE_SE3:QUAT 266 1253 -3.72451 1.70323 -0.0124971 -0.00380829 0.00043965 0.999976 0.00572785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.71022e-06 0.0152338 4.00023 -0.00158408 0.00018988 +EDGE_SE3:QUAT 812 1253 2.76811 1.95913 0.0604421 0.0066475 0.00547475 -0.343039 0.939282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 -0.000231359 0.061529 3.99982 -0.0116216 3.53024 +EDGE_SE3:QUAT 813 1253 -2.52515 2.02129 0.047541 0.00687684 0.00287151 -0.100205 0.994939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 8.31752e-05 0.0308407 3.99993 -0.00167546 3.96007 +EDGE_SE3:QUAT 814 1253 -7.15335 -0.776925 -0.0537775 0.00527746 -0.00282814 0.178869 0.983855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.19816e-05 -0.0326353 3.99993 -0.0032216 3.87229 +EDGE_SE3:QUAT 1254 1255 4.01975 -0.0783207 0.0143827 -0.00139272 0.00158682 0.00217691 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -8.74182e-06 0.0127309 3.99999 1.3786e-05 4.00002 +EDGE_SE3:QUAT 263 1254 4.97293 1.41368 0.00965815 0.00331488 0.000789824 -0.999741 0.0225017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 4.57255e-06 0.0132696 4.00018 0.00255902 0.00207098 +EDGE_SE3:QUAT 264 1254 0.674783 1.46859 0.00610962 0.00447584 0.00296615 -0.999845 0.0167884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.59912e-05 0.017911 4.0003 0.0112565 0.00123931 +EDGE_SE3:QUAT 265 1254 -3.55738 1.60804 -0.00311461 0.00284621 0.000906116 -0.999971 0.00706876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.98108e-06 0.0113857 4.00013 0.00346322 0.000235278 +EDGE_SE3:QUAT 812 1254 5.85048 -0.766536 0.0168539 0.00730087 0.00396837 -0.341285 0.939923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 -0.00010424 0.053951 3.99983 -0.0105476 3.53482 +EDGE_SE3:QUAT 813 1254 1.49944 1.09791 0.0344679 0.00781292 0.00166447 -0.098256 0.995129 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.35485e-05 0.0222752 3.99996 -0.00124084 3.9615 +EDGE_SE3:QUAT 814 1254 -3.27121 0.585727 -0.00106035 0.00657578 -0.00374256 0.180945 0.983464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 -4.48786e-05 -0.0424514 3.99988 -0.00422253 3.86948 +EDGE_SE3:QUAT 815 1254 -7.09529 -2.33583 -0.0152669 0.00852134 -0.00255784 0.443448 0.896256 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 0.000129918 -0.0541423 3.99984 -0.014766 3.21414 +EDGE_SE3:QUAT 1255 1256 3.97739 -0.0725255 0.03029 3.92368e-05 -0.00104369 0.00275981 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.16722e-08 -0.00835076 4 -1.15229e-05 3.99999 +EDGE_SE3:QUAT 262 1255 5.43097 1.25255 0.020783 0.00561847 -0.000637283 -0.999545 0.029632 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -3.64483e-05 0.0225031 4.0005 -0.00387499 0.00364269 +EDGE_SE3:QUAT 263 1255 0.951838 1.30585 0.000416941 0.00491313 0.00206145 -0.999685 0.0245082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 2.6784e-05 0.0196703 4.00038 0.00727164 0.00251262 +EDGE_SE3:QUAT 264 1255 -3.3341 1.41429 -0.0217096 0.00619553 0.0043906 -0.999792 0.0189365 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 9.37211e-05 0.0247957 4.00056 0.0166118 0.00165713 +EDGE_SE3:QUAT 813 1255 5.42316 0.24291 0.0264076 0.00674685 0.00342478 -0.0959762 0.995355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 8.58932e-05 0.0347438 3.99992 -0.00178294 3.96345 +EDGE_SE3:QUAT 814 1255 0.5103 1.94127 0.0462001 0.00471684 -0.00247486 0.182912 0.983115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -2.50103e-05 -0.0289367 3.99994 -0.00292979 3.86638 +EDGE_SE3:QUAT 815 1255 -4.59921 0.803307 0.0491206 0.00675592 -0.0016875 0.445808 0.895101 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 6.0747e-05 -0.0410392 3.9999 -0.0114271 3.20544 +EDGE_SE3:QUAT 1256 1257 4.0782 -0.0656403 0.0280312 -0.000252686 -0.00288414 0.00197869 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 3.30931e-06 -0.0230676 3.99997 -2.28722e-05 4.00012 +EDGE_SE3:QUAT 210 1256 1.11943 6.22944 0.13474 0.00889449 0.00825381 -0.45167 0.892103 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00164 -0.000902204 0.0885852 3.99984 -0.0217887 3.18594 +EDGE_SE3:QUAT 261 1256 5.91034 0.965084 0.0357511 0.00622296 0.00360325 -0.999486 0.031227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 6.25964e-05 0.0249288 4.0006 0.0128275 0.0040972 +EDGE_SE3:QUAT 262 1256 1.45596 1.09073 0.002662 0.00450829 -0.000623405 -0.999461 0.0325168 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -2.67867e-05 0.0180614 4.00032 -0.00365899 0.00431436 +EDGE_SE3:QUAT 263 1256 -3.02523 1.19524 -0.0137142 0.00404155 0.00208657 -0.999612 0.0274907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 2.35237e-05 0.0161848 4.00025 0.00744302 0.00310235 +EDGE_SE3:QUAT 264 1256 -7.2948 1.34124 -0.0424124 0.00521736 0.00458572 -0.999744 0.0215179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.4593e-05 0.0208845 4.00038 0.0174264 0.00203713 +EDGE_SE3:QUAT 814 1256 4.25988 3.30078 0.103472 0.00512025 -0.00356553 0.185717 0.982584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -1.4009e-05 -0.0382122 3.9999 -0.00385258 3.8624 +EDGE_SE3:QUAT 815 1256 -2.14554 3.92326 0.115383 0.0070848 -0.00283264 0.447876 0.894063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 0.000150378 -0.0491884 3.99989 -0.0132032 3.19823 +EDGE_SE3:QUAT 1257 1258 4.0165 -0.14355 0.000528269 -0.00333231 0.00111688 -0.0323616 0.99947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.27434e-05 0.00762769 4 -0.000116446 3.99583 +EDGE_SE3:QUAT 210 1257 3.4608 2.92782 0.0680338 0.00732973 0.00590683 -0.449844 0.893057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00094 -0.000486849 0.0679101 3.99988 -0.0169277 3.19171 +EDGE_SE3:QUAT 211 1257 -2.82258 3.10795 0.0681153 0.0093877 0.00264993 -0.190298 0.981678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 0.000126642 0.0409789 3.99987 -0.00453689 3.85556 +EDGE_SE3:QUAT 260 1257 6.32142 0.56915 0.0232138 0.00305735 0.005047 -0.999761 0.0210702 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.08516e-05 0.0122383 4.00006 0.0196513 0.00190985 +EDGE_SE3:QUAT 261 1257 1.86033 0.776268 0.0108511 0.00332778 0.00415446 -0.999433 0.0332537 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.00795e-05 0.0133346 4.00013 0.0156885 0.00452935 +EDGE_SE3:QUAT 262 1257 -2.60877 0.895788 -0.00995842 0.00199655 -0.000133169 -0.999401 0.034554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.33699e-06 0.00800044 4.00006 -0.00108237 0.00479222 +EDGE_SE3:QUAT 263 1257 -7.06902 1.03554 -0.0165385 0.00136789 0.00211128 -0.999549 0.0299147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.11083e-05 0.00547938 4.00002 0.00809923 0.00360349 +EDGE_SE3:QUAT 815 1257 0.347749 7.1392 0.187703 0.00825742 -0.00541422 0.449799 0.893075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00093 0.000447531 -0.0694354 3.99985 -0.0177379 3.19193 +EDGE_SE3:QUAT 1258 1259 4.00008 -0.398483 -0.0061603 -0.00243598 0.0096987 -0.105121 0.994409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00132 -0.000305953 0.0732766 3.99969 -0.00378356 3.95714 +EDGE_SE3:QUAT 210 1258 5.72472 -0.369432 0.000483191 0.00509153 0.00871151 -0.478518 0.87802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00117 -0.000848307 0.0719772 4.00005 -0.0172409 3.08536 +EDGE_SE3:QUAT 211 1258 0.850966 1.47102 0.0328259 0.00634991 0.00451654 -0.221679 0.975089 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -1.38782e-05 0.0498457 3.99984 -0.00604258 3.80405 +EDGE_SE3:QUAT 212 1258 -3.98979 0.619645 -0.0670869 0.00319663 -0.00927104 0.0479446 0.998802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00139 -1.9693e-05 -0.0757721 3.99964 -0.00182393 3.99224 +EDGE_SE3:QUAT 259 1258 6.4786 0.300298 -0.024705 0.00496992 -0.00699372 0.99957 0.028057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000131656 -0.0199054 4.00025 0.0268085 0.00342772 +EDGE_SE3:QUAT 260 1258 2.29498 0.531418 0.00633697 -0.00404856 -0.0081398 0.999894 0.0113982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000129999 0.0161988 3.99998 0.0329194 0.000856238 +EDGE_SE3:QUAT 261 1258 -2.15744 0.662541 -0.0128381 0.0044686 0.00746045 -0.999962 0.000769664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000133346 0.0178757 4.0001 0.0298167 0.000304501 +EDGE_SE3:QUAT 262 1258 -6.60287 0.770452 -0.0141326 0.00294176 0.00293342 -0.999989 0.00209994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.42273e-05 0.0117672 4.0001 0.0116846 8.63876e-05 +EDGE_SE3:QUAT 1259 1260 4.20627 -0.80123 0.00175093 -0.00220126 0.00289576 -0.18362 0.982991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -4.08467e-05 0.0172631 3.99999 -0.0014002 3.86521 +EDGE_SE3:QUAT 211 1259 4.2745 -0.616321 -0.0198638 0.00584219 0.0152672 -0.322964 0.94627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00374 -0.00160114 0.124711 3.99947 -0.0202613 3.58665 +EDGE_SE3:QUAT 212 1259 0.000358266 0.602079 0.00464908 0.00145194 0.000919273 -0.0571691 0.998363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.85815e-06 0.00831207 4 -0.00024671 3.98694 +EDGE_SE3:QUAT 213 1259 -4.50356 -0.650219 -0.0106052 0.00453136 -0.00211681 0.217534 0.97604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -1.75809e-05 -0.027203 3.99995 -0.00334119 3.8109 +EDGE_SE3:QUAT 258 1259 6.972 0.673099 0.0199888 -0.00432402 -0.00899615 0.988466 0.151115 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.71337e-05 0.0176317 3.99974 0.0390542 0.0918108 +EDGE_SE3:QUAT 259 1259 2.54358 0.922409 0.0154079 -0.0040866 -0.00872761 0.991065 0.133033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.99073e-05 0.0166118 3.99977 0.0376474 0.071221 +EDGE_SE3:QUAT 260 1259 -1.65821 1.02717 -0.0192441 -0.0130541 -0.0108812 0.99302 0.116718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 0.000808521 0.0531508 4.00142 0.0541083 0.0559462 +EDGE_SE3:QUAT 261 1259 -6.13754 1.05012 -0.0401747 -0.0135145 -0.0101187 0.994386 0.104458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 0.000820935 0.0548578 4.00178 0.0505844 0.0450501 +EDGE_SE3:QUAT 1260 1261 3.92032 -0.768615 0.0071855 0.00352869 -0.0008826 -0.181085 0.983461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.09369e-06 0.000783991 4 -0.000313027 3.86883 +EDGE_SE3:QUAT 212 1260 4.09822 -0.670737 -0.00813335 -0.000854209 0.00414332 -0.239853 0.9708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -8.9414e-05 0.0279644 3.99997 -0.00313703 3.77008 +EDGE_SE3:QUAT 213 1260 -0.338676 0.428526 0.0109009 0.00207972 0.00126592 0.0343974 0.999405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.04682e-05 0.00925159 4 0.000154163 3.99529 +EDGE_SE3:QUAT 214 1260 -4.47134 -0.577596 0.00719768 -0.00234026 0.00030516 0.256499 0.966542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.54574e-06 0.00909172 3.99999 0.0014624 3.73685 +EDGE_SE3:QUAT 258 1260 3.18956 2.66899 0.015403 -0.00583411 -0.0113825 0.94397 0.329785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000111266 0.0235571 3.99941 0.0473459 0.435802 +EDGE_SE3:QUAT 259 1260 -1.31361 2.80386 0.0119829 -0.0056013 -0.0109693 0.949702 0.312913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.10914e-05 0.0227591 3.99946 0.046157 0.392379 +EDGE_SE3:QUAT 260 1260 -5.54935 2.78661 -0.100823 -0.0140556 -0.015147 0.954627 0.297085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 0.000604466 0.0600133 3.99949 0.0781025 0.355614 +EDGE_SE3:QUAT 1261 1262 3.98043 -0.804755 0.00342582 0.00356994 0.00353122 -0.170589 0.98533 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -5.57079e-06 0.0341937 3.99993 -0.0030874 3.88389 +EDGE_SE3:QUAT 213 1261 3.59808 -0.0759889 0.00852126 0.00544596 0.000882031 -0.146899 0.989136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 4.15889e-05 0.0162908 3.99998 -0.00142545 3.91375 +EDGE_SE3:QUAT 214 1261 -0.703315 0.681173 0.0150895 0.00118677 8.6513e-06 0.0769629 0.997033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.06774e-07 -0.00102312 4 -5.34377e-05 3.97631 +EDGE_SE3:QUAT 215 1261 -4.83187 0.0474415 -0.120524 -0.00481215 -0.0116106 0.217558 0.975967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00127 0.000674424 -0.0742159 3.99979 -0.00739085 3.81203 +EDGE_SE3:QUAT 258 1261 0.620736 5.69804 0.0307161 -0.00155212 -0.00920626 0.868816 0.495048 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.000101054 -0.000897457 3.99998 0.0209538 0.980484 +EDGE_SE3:QUAT 259 1261 -4.0034 5.74128 0.0202255 -0.00156508 -0.0088745 0.877297 0.479863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.00010579 0.00017655 3.99995 0.0214255 0.921264 +EDGE_SE3:QUAT 1262 1263 4.22623 -0.517963 -0.0444016 -0.000178205 0.00732299 -0.0894533 0.995964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 -0.000118011 0.0577023 3.9998 -0.0025691 3.96882 +EDGE_SE3:QUAT 213 1262 7.16444 -2.00545 -0.00812331 0.00926406 0.0047914 -0.31358 0.949505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 -9.27365e-05 0.0654063 3.99974 -0.0117425 3.60773 +EDGE_SE3:QUAT 214 1262 3.35411 0.478073 0.015473 0.00456906 0.00395792 -0.0941255 0.995542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 4.24708e-05 0.0363756 3.99991 -0.00178442 3.96489 +EDGE_SE3:QUAT 215 1262 -0.8952 0.981754 -0.0221827 0.000144987 -0.00799477 0.0482092 0.998805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00102 6.91838e-05 -0.0638333 3.99975 -0.00153837 3.99172 +EDGE_SE3:QUAT 216 1262 -5.33337 0.800417 -0.0225707 0.000643651 -0.00871799 0.101508 0.994796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0012 0.000162611 -0.0694657 3.99971 -0.0035222 3.95999 +EDGE_SE3:QUAT 1263 1264 4.10957 -0.20373 -0.0112258 -0.00078834 0.00613159 -0.022805 0.999721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00059 -3.96324e-05 0.0488051 3.99985 -0.000556458 3.99852 +EDGE_SE3:QUAT 214 1263 7.398 -0.80331 -0.0676996 0.00459961 0.0117214 -0.182994 0.983033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00237 -0.000436385 0.0990286 3.99945 -0.00921909 3.8685 +EDGE_SE3:QUAT 215 1263 3.35812 0.875833 0.00642874 0.000291058 -0.00065116 -0.041453 0.99914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.12993e-06 -0.00505125 4 0.000103605 3.99313 +EDGE_SE3:QUAT 216 1263 -1.09274 1.16365 0.00892234 0.000578298 -0.00133937 0.0118406 0.999929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.61335e-06 -0.0107949 3.99999 -6.40428e-05 3.99947 +EDGE_SE3:QUAT 217 1263 -5.12877 1.21537 0.0534399 0.00333779 0.000294982 0.0169155 0.999851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.44987e-06 0.00168141 4 1.23121e-05 3.99886 +EDGE_SE3:QUAT 1264 1265 4.27514 -0.113246 0.0399614 -0.00181323 -0.000450286 -0.00478201 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.36718e-06 -0.0037062 4 8.93517e-06 3.99991 +EDGE_SE3:QUAT 215 1264 7.41881 0.320921 0.00174995 -0.0001083 0.00528171 -0.0640569 0.997932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -4.47039e-05 0.0419149 3.99989 -0.00133926 3.98403 +EDGE_SE3:QUAT 216 1264 3.01092 1.03205 0.0114778 -0.000328609 0.00449164 -0.0108315 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -1.11291e-05 0.0358866 3.99992 -0.000194464 3.99985 +EDGE_SE3:QUAT 217 1264 -1.02956 1.14375 0.0397435 0.00243296 0.00634637 -0.00630004 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00063 5.59648e-05 0.0509587 3.99984 -0.000158413 4.00049 +EDGE_SE3:QUAT 218 1264 -5.27095 1.22187 -0.0226374 0.00555286 0.00159877 -0.00564051 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 3.65372e-05 0.0131649 3.99999 -3.71253e-05 3.99992 +EDGE_SE3:QUAT 1265 1266 4.38717 -0.0894744 0.0224271 -0.00264 -0.00714265 -0.00181007 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00079 7.33596e-05 -0.0572079 3.9998 4.85815e-05 4.0008 +EDGE_SE3:QUAT 216 1265 7.25024 0.843815 0.0122555 -0.00240593 0.00420748 -0.015575 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -4.6238e-05 0.0331997 3.99993 -0.00025839 3.99931 +EDGE_SE3:QUAT 217 1265 3.23826 0.97586 0.0215264 0.000423782 0.00595349 -0.0106395 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 1.0437e-06 0.0476799 3.99986 -0.00025346 4.00012 +EDGE_SE3:QUAT 218 1265 -1.01637 1.0509 0.0106926 0.00333086 0.00108367 -0.0101986 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.50315e-05 0.00907549 3.99999 -4.68686e-05 3.9996 +EDGE_SE3:QUAT 219 1265 -5.38336 1.15666 0.0253461 0.0048687 0.00635528 -0.0112982 0.999904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 0.000114772 0.0514982 3.99983 -0.00028745 4.00015 +EDGE_SE3:QUAT 1266 1267 4.30436 -0.0952666 0.0239535 0.00169146 -0.00627775 0.00021884 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 -4.22953e-05 -0.0502331 3.99984 -3.89856e-06 4.00063 +EDGE_SE3:QUAT 218 1266 3.36611 0.888498 0.0213189 0.000495796 -0.00596599 -0.0122561 0.999907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 -2.22535e-05 -0.0476501 3.99986 0.000292363 3.99997 +EDGE_SE3:QUAT 219 1266 -0.999849 0.958339 0.00272893 0.0017734 -0.000673804 -0.0128857 0.999915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.58341e-06 -0.00511488 4 3.23805e-05 3.99934 +EDGE_SE3:QUAT 220 1266 -5.2328 1.08618 -0.00346361 -0.000763695 0.00358649 -0.0155628 0.999872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -1.56454e-05 0.0285401 3.99995 -0.000221949 3.99923 +EDGE_SE3:QUAT 1267 1268 4.20989 -0.101247 -0.00227339 0.00203031 0.00196216 0.00114479 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.60036e-05 0.0156695 3.99998 9.1512e-06 4.00006 +EDGE_SE3:QUAT 219 1267 3.29876 0.750526 0.0241228 0.00346411 -0.00716474 -0.0125269 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 -0.000113326 -0.0567927 3.9998 0.000358998 4.00018 +EDGE_SE3:QUAT 220 1267 -0.941581 0.857693 -0.00987499 0.000839454 -0.00268202 -0.0155395 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.15659e-05 -0.0212924 3.99997 0.000165167 3.99915 +EDGE_SE3:QUAT 221 1267 -5.10138 0.96164 -0.0143174 -0.00381389 -0.00121692 -0.0180768 0.999829 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.9926e-05 -0.0105576 3.99999 9.77487e-05 3.99872 +EDGE_SE3:QUAT 1268 1269 4.09038 -0.0985277 0.0174486 0.00268807 0.00666051 0.00103644 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 7.27017e-05 0.0532583 3.99982 3.04663e-05 4.0007 +EDGE_SE3:QUAT 220 1268 3.25353 0.62682 0.00951496 0.00301418 -0.000684387 -0.0143103 0.999893 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.34598e-06 -0.00495581 4 3.42501e-05 3.99919 +EDGE_SE3:QUAT 221 1268 -0.927725 0.715128 0.00663054 -0.00208781 0.000790321 -0.0172987 0.999848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.22532e-06 0.00588639 4 -4.96839e-05 3.99881 +EDGE_SE3:QUAT 222 1268 -5.03385 0.824324 -0.0498473 -0.00397839 -0.004422 -0.0202489 0.999777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 6.29895e-05 -0.0363225 3.99992 0.000369063 3.99869 +EDGE_SE3:QUAT 1269 1270 4.23211 -0.0903724 0.0395441 0.000709835 0.00264673 0.00243862 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 7.91516e-06 0.0211534 3.99997 2.59051e-05 4.00009 +EDGE_SE3:QUAT 220 1269 7.32433 0.414748 0.0344494 0.00577956 0.00618676 -0.0129536 0.99988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 0.000134275 0.0503845 3.99984 -0.000322913 3.99996 +EDGE_SE3:QUAT 221 1269 3.14714 0.497187 0.0128739 0.00089145 0.00749025 -0.0164202 0.999837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0009 4.61411e-06 0.0600852 3.99977 -0.000492806 3.99982 +EDGE_SE3:QUAT 222 1269 -0.955849 0.581056 0.0057295 -0.00127143 0.00223952 -0.0188071 0.99982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.33454e-05 0.0176201 3.99998 -0.00016492 3.99866 +EDGE_SE3:QUAT 223 1269 -5.08211 0.670943 -0.0881416 -0.00133559 -0.0043421 -0.0201637 0.999786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 1.42217e-05 -0.035041 3.99992 0.00035375 3.99868 +EDGE_SE3:QUAT 1270 1271 4.23793 -0.0832059 0.0130887 -0.000949972 -0.00253657 0.00220791 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 9.96378e-06 -0.0202676 3.99997 -2.25132e-05 4.00008 +EDGE_SE3:QUAT 221 1270 7.38797 0.260756 -0.0145438 0.00184278 0.0102643 -0.0135984 0.999853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00168 4.15268e-05 0.0824227 3.99958 -0.000556974 4.00096 +EDGE_SE3:QUAT 222 1270 3.26604 0.323479 0.0234663 -0.000419196 0.00482364 -0.0167414 0.999848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -1.7376e-05 0.0384918 3.99991 -0.000322234 3.99925 +EDGE_SE3:QUAT 223 1270 -0.876083 0.419203 -0.0142207 -0.000474467 -0.00168664 -0.0180849 0.999835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.98291e-06 -0.0135896 3.99999 0.000123145 3.99874 +EDGE_SE3:QUAT 224 1270 -4.95148 0.491512 -0.0265904 0.00100352 0.000693533 -0.0158991 0.999873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.71716e-06 0.00573759 4 -4.6101e-05 3.999 +EDGE_SE3:QUAT 1271 1272 4.33299 -0.0821596 -0.00795936 -0.000902129 0.00165453 0.00248715 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -5.8228e-06 0.0132631 3.99999 1.64458e-05 4.00002 +EDGE_SE3:QUAT 223 1271 3.35564 0.179728 0.0123482 -0.00133851 -0.00430558 -0.0151384 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 1.64575e-05 -0.0346781 3.99992 0.000262519 3.99938 +EDGE_SE3:QUAT 224 1271 -0.727843 0.256734 -0.00961536 -0.000146099 -0.00174537 -0.0130642 0.999913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 6.46159e-08 -0.0139824 3.99999 9.13688e-05 3.99937 +EDGE_SE3:QUAT 225 1271 -4.80117 0.321211 -0.0110984 0.00210569 -0.0014285 -0.00850863 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.21331e-05 -0.0112117 3.99999 4.74926e-05 3.99974 +EDGE_SE3:QUAT 1272 1273 4.42034 -0.081149 -0.00529332 -0.00212979 0.00404544 0.00278921 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 -3.34728e-05 0.0324361 3.99993 4.44368e-05 4.00023 +EDGE_SE3:QUAT 224 1272 3.62236 0.0749069 0.00153173 -0.00102153 -9.30275e-05 -0.0107471 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.66858e-07 -0.000875821 4 4.94174e-06 3.99954 +EDGE_SE3:QUAT 225 1272 -0.484099 0.172441 0.00125782 0.00111549 0.000420093 -0.00577574 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.90647e-06 0.00343789 4 -9.99755e-06 3.99987 +EDGE_SE3:QUAT 226 1272 -5.00704 0.182254 -0.00109274 0.0019123 -0.00200763 0.00744329 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.48417e-05 -0.0162306 3.99998 -6.04294e-05 3.99984 +EDGE_SE3:QUAT 1273 1274 4.36446 -0.0716169 0.0385608 -0.000368409 -0.00407892 0.00281621 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 7.13302e-06 -0.0326204 3.99993 -4.60821e-05 4.00023 +EDGE_SE3:QUAT 225 1273 3.94067 0.0428971 -0.0115886 -0.000905426 0.00450074 -0.00303837 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -1.77598e-05 0.0359749 3.99992 -5.50867e-05 4.00029 +EDGE_SE3:QUAT 226 1273 -0.595701 0.164392 0.00588739 -3.31521e-05 0.00189674 0.0101296 0.999947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 6.23257e-07 0.0151758 3.99999 7.68652e-05 3.99965 +EDGE_SE3:QUAT 227 1273 -4.81902 0.133634 -0.00253428 0.00017842 0.00456679 0.0323942 0.999465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 1.93821e-05 0.0364102 3.99992 0.000589272 3.99613 +EDGE_SE3:QUAT 1274 1275 4.13866 -0.0952871 0.0521526 0.00312975 -0.00249384 -0.00654027 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -3.16647e-05 -0.0197039 3.99998 6.46274e-05 3.99993 +EDGE_SE3:QUAT 226 1274 3.75015 0.189225 0.0243536 -0.000466938 -0.00211637 0.0135641 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 5.37544e-06 -0.0168505 3.99998 -0.000114154 3.99934 +EDGE_SE3:QUAT 227 1274 -0.473774 0.34572 8.54175e-05 -0.000161106 0.000568885 0.0355686 0.999367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -9.09123e-08 0.00461115 4 8.23615e-05 3.99494 +EDGE_SE3:QUAT 228 1274 -4.56176 0.427569 -0.057038 -0.00462065 0.000664233 0.0463926 0.998912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -1.92126e-05 0.00786522 4 0.000202109 3.99141 +EDGE_SE3:QUAT 1275 1276 4.36841 -0.24339 0.0256051 -0.00212862 -0.00291465 -0.0533952 0.998567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.47717e-05 -0.0245795 3.99996 0.000667052 3.98875 +EDGE_SE3:QUAT 227 1275 3.6599 0.540678 0.0433282 0.00293156 -0.00171413 0.0288765 0.999577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.97777e-05 -0.0147112 3.99999 -0.000216986 3.99672 +EDGE_SE3:QUAT 228 1275 -0.443547 0.694602 -0.00374544 -0.00152003 -0.00142803 0.0397207 0.999209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.67333e-06 -0.0106734 3.99999 -0.000207073 3.99372 +EDGE_SE3:QUAT 229 1275 -4.75883 1.05193 -0.0375091 -0.0035471 0.000630055 0.00479851 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.37324e-06 0.00524443 4 1.27099e-05 3.99991 +EDGE_SE3:QUAT 1276 1277 4.08961 -0.509676 -0.0318739 -0.0033163 0.0171753 -0.130332 0.991316 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0041 -0.00105234 0.128898 3.99909 -0.008256 3.9362 +EDGE_SE3:QUAT 228 1276 3.93986 0.801219 0.0307274 -0.00325409 -0.00465141 -0.0136668 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 5.44433e-05 -0.0377368 3.99991 0.000257393 3.99961 +EDGE_SE3:QUAT 229 1276 -0.392004 0.863975 -0.015082 -0.00561615 -0.00230957 -0.0483492 0.998812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.58587e-05 -0.0216648 3.99997 0.000548575 3.99077 +EDGE_SE3:QUAT 230 1276 -4.30043 1.58044 -0.120491 -0.00898266 -0.0148421 -0.158032 0.987282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00397 -0.000380463 -0.131186 3.99896 0.0106663 3.9044 +EDGE_SE3:QUAT 1277 1278 3.93899 -0.681423 0.0119591 0.0015929 -0.00393197 -0.161705 0.98683 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -6.90974e-05 -0.0271938 3.99996 0.00208229 3.89559 +EDGE_SE3:QUAT 229 1277 3.6381 -0.0514941 -0.0158776 -0.00755921 0.0142463 -0.17866 0.983779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0019 -0.000968489 0.0927202 3.99963 -0.00767526 3.87445 +EDGE_SE3:QUAT 230 1277 -0.588981 -0.1697 -0.00938582 -0.00740225 0.00153178 -0.285721 0.958283 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 7.61414e-05 -0.0132138 3.99997 0.00316791 3.67348 +EDGE_SE3:QUAT 231 1277 -4.65957 1.03207 0.0370582 -0.00463506 0.011217 -0.461812 0.886895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -0.000524465 0.0405743 4.00018 -0.00487593 3.14721 +EDGE_SE3:QUAT 1278 1279 4.27577 -0.813417 0.00322983 -0.00135424 -0.000938552 -0.181341 0.983419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.16459e-06 -0.0100235 3.99999 0.000986347 3.86849 +EDGE_SE3:QUAT 229 1278 7.06111 -2.06389 -0.0855142 -0.00869378 0.00854004 -0.335109 0.9421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000187959 0.0247883 4.00004 -0.00152033 3.55089 +EDGE_SE3:QUAT 230 1278 2.32418 -2.87482 0.0196845 -0.00701297 -0.00401845 -0.436731 0.899556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 -0.000242548 -0.055493 3.99988 0.0139684 3.23783 +EDGE_SE3:QUAT 231 1278 -2.9707 -2.58582 0.00395463 -0.00662469 0.00585875 -0.599058 0.800657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000136875 -0.0121701 3.99991 0.0112677 2.56447 +EDGE_SE3:QUAT 1279 1280 3.99586 -0.694316 -0.0130077 0.00567712 0.0139756 -0.142107 0.989736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00335 -0.000391159 0.118075 3.99917 -0.00852693 3.9227 +EDGE_SE3:QUAT 231 1279 -2.54084 -6.90835 0.020314 -0.00901636 0.00455068 -0.734516 0.678516 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.33256e-05 -0.0395151 3.99976 0.0274641 1.8423 +EDGE_SE3:QUAT 1280 1281 4.32974 -0.484958 -0.00176581 0.00429947 2.32967e-05 -0.0773933 0.996991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.14989e-05 0.00416171 4 -0.00021251 3.97604 +EDGE_SE3:QUAT 1281 1282 4.11636 -0.154358 0.0191801 -0.00174376 -0.000513261 -0.0149288 0.999887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.83568e-06 -0.00441704 4 3.3732e-05 3.99911 +EDGE_SE3:QUAT 942 1281 1.70074 -6.19389 0.0773484 -0.0021136 0.00666387 0.910734 0.412935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 5.98181e-05 0.0140788 4.00026 -0.0102065 0.682171 +EDGE_SE3:QUAT 1282 1283 3.97622 -0.107225 0.0188768 -0.00106707 -0.00159982 -0.00439981 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.5964e-06 -0.0128546 3.99999 2.82547e-05 3.99996 +EDGE_SE3:QUAT 941 1282 4.7811 -2.35544 0.0296608 -0.00598579 -0.00211369 0.975602 0.219453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000179629 0.025432 4.00036 0.0174596 0.192884 +EDGE_SE3:QUAT 942 1282 -0.871707 -3.00061 0.0560006 -0.0024626 0.00477159 0.904359 0.426739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.84451e-05 0.015119 4.00023 -0.00409829 0.728506 +EDGE_SE3:QUAT 943 1282 -6.21487 -1.54224 0.0613108 0.000229496 0.00193581 0.802859 0.596166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.63188e-06 0.00202045 4.00001 -0.00250324 1.42166 +EDGE_SE3:QUAT 1221 1282 4.1652 5.23658 0.112859 0.00894575 0.00343664 -0.488818 0.872333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -0.00030509 0.0623819 3.99985 -0.0184259 3.0452 +EDGE_SE3:QUAT 1222 1282 -1.87425 5.68078 0.121915 0.00741819 0.00639869 -0.324756 0.945747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00101 -0.000277879 0.0702036 3.99975 -0.0124768 3.57936 +EDGE_SE3:QUAT 1283 1284 4.04094 -0.0977465 0.0156894 0.00137796 -0.00179812 -0.0025284 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.00681e-05 -0.0143431 3.99999 1.8222e-05 4.00003 +EDGE_SE3:QUAT 940 1283 5.32677 0.52163 0.0353238 -0.00681718 -0.00185296 0.998994 0.0442912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 9.70037e-05 0.0273473 4.0007 0.00978887 0.00805817 +EDGE_SE3:QUAT 941 1283 1.2336 -0.556444 0.00927388 -0.00484391 -0.0035755 0.97461 0.223827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000113335 0.0204565 4.00012 0.0207829 0.200614 +EDGE_SE3:QUAT 942 1283 -3.2985 0.121161 0.0437816 -0.00160086 0.00317405 0.902432 0.430818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.87534e-05 0.00995412 4.0001 -0.00271098 0.742454 +EDGE_SE3:QUAT 1221 1283 6.15522 1.78917 0.0787877 0.007641 0.00247427 -0.492865 0.870069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -0.000183809 0.0509194 3.99989 -0.0154276 3.02898 +EDGE_SE3:QUAT 1222 1283 1.21305 3.14767 0.0656334 0.00561887 0.00537775 -0.329099 0.944263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -0.000205945 0.0568232 3.99985 -0.0101428 3.56758 +EDGE_SE3:QUAT 1223 1283 -3.95406 2.78494 -0.0171833 6.20738e-05 0.000223565 -0.163941 0.98647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.50314e-07 0.00183684 4 -0.000151891 3.89249 +EDGE_SE3:QUAT 1284 1285 4.07159 -0.0966004 -0.0245987 -0.000589586 0.00168056 -0.00177186 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -4.07846e-06 0.013432 3.99999 -1.19363e-05 4.00003 +EDGE_SE3:QUAT 939 1284 5.20569 1.9598 -0.0131958 -0.00361274 0.00101636 -0.991942 0.126634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -4.85189e-05 -0.014778 4.00017 0.00750521 0.0642147 +EDGE_SE3:QUAT 940 1284 1.3167 0.970081 -0.00301288 -0.00503171 -0.000663311 0.998887 0.046889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 4.11028e-05 0.0201924 4.00039 0.00452266 0.0089016 +EDGE_SE3:QUAT 941 1284 -2.34628 1.30086 -0.0127903 -0.0028338 -0.00266031 0.974071 0.226208 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.63779e-05 0.0119253 4.00002 0.0141706 0.204768 +EDGE_SE3:QUAT 942 1284 -5.7771 3.3456 0.0319999 0.000612505 0.00374473 0.901276 0.433228 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.14882e-05 -0.000601088 3.99998 -0.010157 0.750784 +EDGE_SE3:QUAT 1222 1284 4.30008 0.563229 0.0207443 0.00618113 0.00325866 -0.33139 0.943468 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -5.98603e-05 0.04468 3.99988 -0.00849291 3.56122 +EDGE_SE3:QUAT 1223 1284 -0.173562 1.37988 -0.00161477 0.00112821 -0.00195625 -0.166456 0.986046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.80553e-05 -0.0127922 3.99999 0.000983862 3.88921 +EDGE_SE3:QUAT 1224 1284 -4.79634 0.946115 0.0227948 0.00287137 -0.000475038 -0.0561453 0.998418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.83319e-06 -0.00185181 4 3.3719e-05 3.98739 +EDGE_SE3:QUAT 1285 1286 4.00001 -0.0817985 0.0139858 -0.00140021 -0.000308229 -0.00177821 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.75008e-06 -0.00249569 4 2.22453e-06 3.99999 +EDGE_SE3:QUAT 938 1285 4.89018 1.9714 0.00264059 0.00066891 0.00508625 -0.956282 0.292402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.20046e-05 0.00401353 4.00001 0.0146982 0.342062 +EDGE_SE3:QUAT 939 1285 1.24809 1.01929 -0.00943287 -0.00201524 0.00167304 -0.992145 0.125069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.94018e-05 -0.00822173 4.00003 0.00841682 0.0626042 +EDGE_SE3:QUAT 940 1285 -2.7127 1.455 -0.0656828 -0.00673829 -0.00110063 0.998781 0.0488961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 8.11426e-05 0.0270483 4.0007 0.00700759 0.00975896 +EDGE_SE3:QUAT 941 1285 -5.93084 3.16423 -0.0476456 -0.00442102 -0.00276432 0.973617 0.228128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.65136e-05 0.0187481 4.00013 0.0172948 0.208338 +EDGE_SE3:QUAT 1223 1285 3.61832 -0.0423043 -0.0105471 0.00111905 -0.00032173 -0.167838 0.985814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.65883e-07 -0.000254348 4 -4.47831e-05 3.88732 +EDGE_SE3:QUAT 1224 1285 -0.758577 0.389993 0.00220349 0.00238026 0.00107988 -0.058001 0.998313 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.0706e-05 0.0102484 3.99999 -0.000312718 3.98657 +EDGE_SE3:QUAT 1225 1285 -4.89509 0.330614 -0.0135145 0.00249884 0.000990741 -0.0251459 0.99968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.04636e-05 0.00867208 4 -0.000112095 3.99749 +EDGE_SE3:QUAT 1286 1287 3.98949 -0.0943994 0.017585 -0.000656589 -0.000787206 -0.00170681 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.0479e-06 -0.00631107 4 5.37996e-06 4 +EDGE_SE3:QUAT 937 1286 5.47639 1.79532 0.0036651 -0.000170916 0.00514489 -0.8312 0.555949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.4813e-05 0.00615275 4.00006 0.00705698 1.23637 +EDGE_SE3:QUAT 938 1286 1.52022 -0.195685 0.00567432 5.0366e-05 0.00617978 -0.956753 0.290837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.59395e-05 0.0014418 3.99995 0.0195424 0.338453 +EDGE_SE3:QUAT 939 1286 -2.64607 0.119088 0.0206418 -0.0024875 0.00308283 -0.992376 0.12318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.2397e-05 -0.010128 4.00002 0.0142804 0.0607705 +EDGE_SE3:QUAT 940 1286 -6.66561 1.92635 -0.107441 -0.00635004 -0.00273758 0.998678 0.0509391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000112741 0.0254961 4.00057 0.0134632 0.0105875 +EDGE_SE3:QUAT 1224 1286 3.19065 -0.15893 0.00349765 0.000980206 0.000926722 -0.0597188 0.998214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 2.65577e-06 0.00807495 4 -0.000247688 3.98575 +EDGE_SE3:QUAT 1225 1286 -0.916005 0.0521741 -0.0072907 0.00105992 0.00072494 -0.0268387 0.999639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.94049e-06 0.00613445 4 -8.38052e-05 3.99713 +EDGE_SE3:QUAT 1226 1286 -5.27656 0.0339834 -0.0333989 0.00182073 0.000315992 -0.0133581 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.61674e-06 0.00281907 4 -1.94718e-05 3.99929 +EDGE_SE3:QUAT 1287 1288 4.2919 -0.104411 0.0221751 0.00157695 -0.00190921 -0.00182021 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.21659e-05 -0.0152393 3.99999 1.39969e-05 4.00004 +EDGE_SE3:QUAT 937 1287 3.87007 -1.83764 0.000888673 -0.00111755 0.00513823 -0.832084 0.554624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 2.46836e-05 0.00100497 4 0.0100138 1.23049 +EDGE_SE3:QUAT 938 1287 -1.83207 -2.33686 0.0102823 -0.000776773 0.00631683 -0.957195 0.289373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.9709e-05 -0.00224744 3.99989 0.0217831 0.335081 +EDGE_SE3:QUAT 939 1287 -6.49232 -0.748304 0.0522829 -0.00321906 0.00347991 -0.992521 0.12198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -5.27832e-05 -0.0131102 4.00005 0.0164996 0.0596286 +EDGE_SE3:QUAT 1224 1287 7.10997 -0.732849 0.0112383 0.000538245 0.000169978 -0.0609932 0.998138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.4125e-07 0.00174522 4 -5.71501e-05 3.98512 +EDGE_SE3:QUAT 1225 1287 3.0459 -0.26361 0.00554542 0.000615431 -2.44799e-05 -0.0280127 0.999607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.4671e-08 1.11622e-05 4 -1.1233e-06 3.99686 +EDGE_SE3:QUAT 1226 1287 -1.29547 -0.170761 -0.0168085 0.0012783 -0.000153795 -0.0150525 0.999886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.955e-07 -0.000999072 4 6.93947e-06 3.99909 +EDGE_SE3:QUAT 1227 1287 -5.27775 -0.49289 -0.0252514 5.10793e-05 0.00167713 0.0388781 0.999243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.95089e-06 0.013363 3.99999 0.000259423 3.994 +EDGE_SE3:QUAT 1288 1289 4.28342 -0.0813795 0.0206019 0.000303418 0.00937722 -0.00114922 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00141 8.96918e-06 0.0750449 3.99965 -4.25216e-05 4.0014 +EDGE_SE3:QUAT 937 1288 2.10869 -5.77464 0.0057648 -0.00197997 0.00301378 -0.832946 0.553343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.40726e-05 -0.00655166 3.99996 0.00997327 1.2248 +EDGE_SE3:QUAT 938 1288 -5.47744 -4.62019 0.0295805 -0.00224761 0.00410802 -0.957757 0.287541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.06207e-06 -0.00925341 3.99993 0.0178782 0.330828 +EDGE_SE3:QUAT 1225 1288 7.33475 -0.609347 0.026647 0.00193177 -0.00180076 -0.0301137 0.999543 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.51578e-05 -0.0136889 3.99999 0.000202655 3.99642 +EDGE_SE3:QUAT 1226 1288 2.98266 -0.401653 0.00194717 0.00268873 -0.00223057 -0.0168027 0.999853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -2.49174e-05 -0.0172951 3.99998 0.000144075 3.99895 +EDGE_SE3:QUAT 1227 1288 -0.986649 -0.263321 -0.010821 0.0017807 -2.23089e-05 0.0371355 0.999309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.09113e-06 -0.000970894 4 -2.29359e-05 3.99448 +EDGE_SE3:QUAT 1228 1288 -4.97436 -1.01706 -0.160094 0.00123608 -0.0130397 0.15905 0.987184 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00263 0.000578791 -0.102763 3.99942 -0.00813761 3.90145 +EDGE_SE3:QUAT 1289 1290 3.98265 -0.0852554 0.0153703 -2.74809e-05 0.000855425 -0.00109487 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.13252e-07 0.00684305 4 -3.74657e-06 4.00001 +EDGE_SE3:QUAT 1226 1289 7.24854 -0.654385 0.0367962 0.00304588 0.00724099 -0.0180063 0.999807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 6.65121e-05 0.058568 3.99978 -0.000525579 3.99956 +EDGE_SE3:QUAT 1227 1289 3.31417 -0.0508118 0.0086286 0.00148106 0.00931933 0.0361041 0.999303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00135 0.000128601 0.0737894 3.99966 0.00133155 3.99615 +EDGE_SE3:QUAT 1228 1289 -0.864636 0.241039 -0.0231782 -0.000109495 -0.00378668 0.157813 0.987462 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 5.28518e-05 -0.0289662 3.99995 -0.00225022 3.90059 +EDGE_SE3:QUAT 1229 1289 -4.8078 -0.614356 -0.0657487 0.00194495 -0.00691714 0.305998 0.952005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 0.000306559 -0.0544547 3.99989 -0.00827171 3.6262 +EDGE_SE3:QUAT 1290 1291 4.38913 -0.0885862 0.0172109 -0.00200245 -0.00093536 -0.00111955 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.50434e-06 -0.00750975 4 4.16655e-06 4.00001 +EDGE_SE3:QUAT 298 1290 1.97921 -6.14513 0.043929 -0.00872332 -0.00269427 0.885766 0.464042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 0.000371729 0.0420737 4.00022 0.0308499 0.862092 +EDGE_SE3:QUAT 299 1290 -4.86102 -5.37246 0.0479914 -0.00402399 0.00129913 0.756471 0.654013 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 0.000148354 0.0255015 4.00008 0.0114812 1.71116 +EDGE_SE3:QUAT 1227 1290 7.30965 0.14688 -0.0514133 0.00151317 0.0103517 0.0346337 0.999345 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00167 0.000149833 0.0820656 3.99958 0.00142205 3.99688 +EDGE_SE3:QUAT 1228 1290 2.93415 1.39021 0.0213147 -0.000199311 -0.00293707 0.156675 0.987646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 3.23893e-05 -0.0222687 3.99997 -0.00171187 3.90194 +EDGE_SE3:QUAT 1229 1290 -1.52152 1.62959 0.00639261 0.00179929 -0.00597557 0.304763 0.952408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 0.000228216 -0.0474803 3.99992 -0.007207 3.62904 +EDGE_SE3:QUAT 1230 1290 -6.18409 0.261995 -0.00081929 0.00245233 -0.0037241 0.469536 0.882902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 0.000158998 -0.0322939 4 -0.00773017 3.1184 +EDGE_SE3:QUAT 1291 1292 4.4124 -0.136042 0.0202371 7.31488e-05 -0.00253575 -0.0173615 0.999846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -3.41554e-06 -0.0202621 3.99997 0.000175842 3.9989 +EDGE_SE3:QUAT 297 1291 4.96413 -1.46528 0.0315603 -0.00727803 -0.00213369 0.97565 0.219201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000264898 0.0309559 4.00057 0.0196814 0.192544 +EDGE_SE3:QUAT 298 1291 -0.429487 -2.4832 0.00546907 -0.00912018 -0.00486761 0.885153 0.465185 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 0.000270106 0.0423565 4 0.0363735 0.86646 +EDGE_SE3:QUAT 299 1291 -5.39507 -1.05896 0.0347018 -0.00474252 -0.00106669 0.755569 0.655051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 5.84594e-05 0.0242365 3.99998 0.0146457 1.71661 +EDGE_SE3:QUAT 1229 1291 2.10863 4.08569 0.0821068 0.00029022 -0.00743418 0.303394 0.952836 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 0.000339253 -0.0524528 3.99992 -0.00756987 3.63249 +EDGE_SE3:QUAT 1230 1291 -3.64737 3.8491 0.0621461 0.00125968 -0.00545175 0.468467 0.883463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000256041 -0.0361234 4.00004 -0.00768828 3.12247 +EDGE_SE3:QUAT 1292 1293 4.32428 -0.273987 0.00712551 -0.000480625 -0.000870538 -0.0608368 0.998147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.86439e-07 -0.0072757 4 0.000224472 3.98521 +EDGE_SE3:QUAT 296 1292 4.71603 1.7174 0.00329986 0.0030696 0.00216843 -0.999992 0.00115297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.64102e-05 0.0122784 4.00013 0.0086458 6.16944e-05 +EDGE_SE3:QUAT 297 1292 1.05374 0.546657 0.000936759 -0.00454324 -0.00272763 0.971665 0.236303 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000102426 0.0193432 4.00013 0.0175278 0.223532 +EDGE_SE3:QUAT 298 1292 -2.80165 1.19969 -0.0114518 -0.00633542 -0.00589237 0.876897 0.4806 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -3.03852e-06 0.0272574 3.9998 0.0298513 0.924382 +EDGE_SE3:QUAT 299 1292 -5.87673 3.31923 0.0315393 -0.00280425 -0.00262557 0.744164 0.667985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.74726e-05 0.00953593 3.99996 0.00913958 1.78489 +EDGE_SE3:QUAT 1230 1292 -1.05223 7.42064 0.132842 0.00265217 -0.00773897 0.453014 0.891466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 0.000549866 -0.0563218 4.00004 -0.012157 3.17989 +EDGE_SE3:QUAT 1293 1294 4.18693 -0.531612 -0.00391373 0.000955533 0.00696192 -0.130701 0.991397 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 -0.000126975 0.0557655 3.99982 -0.00364623 3.93245 +EDGE_SE3:QUAT 295 1293 3.97289 2.54682 -0.0140311 -0.00160565 0.00620931 -0.993735 0.11158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.28088e-06 -0.0064726 3.99985 0.0254825 0.0499757 +EDGE_SE3:QUAT 296 1293 0.419709 1.98581 -0.0117203 -0.00260335 -0.00290204 0.998203 0.0597878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.41975e-05 0.0104643 4.00005 0.0127456 0.0143665 +EDGE_SE3:QUAT 297 1293 -2.64716 2.7544 -0.0200018 -0.00411564 -0.00355411 0.955319 0.295528 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.67331e-05 0.0177412 4.00001 0.02009 0.349538 +EDGE_SE3:QUAT 298 1293 -4.89047 4.97955 -0.0181093 -0.00566232 -0.00707074 0.845902 0.533261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000121005 0.0214784 3.99975 0.0276025 1.13787 +EDGE_SE3:QUAT 1294 1295 4.21621 -0.755625 0.0166424 0.000415251 -0.00183412 -0.16925 0.985571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.44398e-05 -0.0132199 3.99999 0.00107685 3.88546 +EDGE_SE3:QUAT 293 1294 6.25393 4.02828 0.0567663 0.00615605 0.00648926 -0.945048 0.326809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.000265393 0.0300533 4.00089 0.00491521 0.427483 +EDGE_SE3:QUAT 294 1294 3.2549 2.5598 -0.00280824 0.00410395 0.00505602 -0.986645 0.162757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 1.55175e-05 0.0172291 4.00032 0.0136968 0.106084 +EDGE_SE3:QUAT 295 1294 -0.212275 2.13685 -0.0130558 -0.00458689 -0.00603569 0.999782 0.0194422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000114246 0.0183585 4.00017 0.0248353 0.00175053 +EDGE_SE3:QUAT 296 1294 -3.66953 3.02636 -0.032836 -0.00891602 -0.0017314 0.981769 0.18986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000362289 0.0374472 4.001 0.019372 0.144644 +EDGE_SE3:QUAT 1295 1296 4.16265 -0.78406 0.00993943 -0.00317185 -0.000858517 -0.174253 0.984695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.49821e-05 -0.0130559 3.99999 0.00132061 3.87859 +EDGE_SE3:QUAT 292 1295 6.16681 3.0536 0.0170603 0.00338713 0.00523788 -0.954934 0.296752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -4.87807e-05 0.0163113 4.00031 0.00915166 0.352348 +EDGE_SE3:QUAT 293 1295 2.4851 2.0163 0.00269275 0.00326352 0.00670753 -0.986733 0.162179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.37727e-05 0.0137878 4.00018 0.0209612 0.105371 +EDGE_SE3:QUAT 294 1295 -0.964944 1.9153 -0.0286688 -0.00167199 -0.00527916 0.999965 0.00624752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.43105e-05 0.0066886 3.99993 0.0211982 0.000279657 +EDGE_SE3:QUAT 295 1295 -4.38497 3.05491 -0.0207953 -0.00182021 -0.00627077 0.982197 0.187743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.50443e-05 0.00732359 3.99984 0.0255372 0.141171 +EDGE_SE3:QUAT 1296 1297 4.29947 -0.775887 0.0158614 0.00515125 0.0175305 -0.148315 0.988771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00513 -0.00078495 0.144842 3.99878 -0.0108479 3.91725 +EDGE_SE3:QUAT 291 1296 6.3362 1.99697 -0.0769328 -0.00993612 0.0109833 -0.975572 0.219179 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000424627 -0.0415908 4 0.0553397 0.193397 +EDGE_SE3:QUAT 292 1296 2.29653 1.34375 0.00297333 0.000642278 0.00844174 -0.99206 0.125479 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.16029e-05 0.00276318 3.99979 0.0318101 0.0632396 +EDGE_SE3:QUAT 293 1296 -1.69361 1.42364 0.0031329 -0.0007278 -0.00991855 0.999875 0.0122744 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.93025e-05 0.00291205 3.99961 0.0397288 0.000999455 +EDGE_SE3:QUAT 294 1296 -5.09501 2.72964 -0.0122082 0.000172746 -0.00842724 0.983581 0.180273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.04192e-05 -0.00111948 3.9998 0.0307601 0.130239 +EDGE_SE3:QUAT 1297 1298 4.01589 -0.451845 0.0104953 0.00746813 -0.00238503 -0.0769607 0.997003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -4.14962e-05 -0.0120399 3.99999 0.000373162 3.97634 +EDGE_SE3:QUAT 290 1297 6.0394 1.02026 0.0649871 0.00741307 0.0113624 -0.993844 0.109959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000238448 0.0303069 4.00082 0.0376528 0.0489565 +EDGE_SE3:QUAT 291 1297 2.11878 0.856786 0.024361 0.00658667 0.00800222 -0.99732 0.0724226 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000154906 0.026578 4.00062 0.0278007 0.0213522 +EDGE_SE3:QUAT 292 1297 -2.03859 1.02426 0.0168732 -0.0173033 -0.00540269 0.999569 0.0230958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99884 0.000532885 0.0692631 4.00457 0.0248184 0.00348775 +EDGE_SE3:QUAT 293 1297 -5.94392 2.29798 0.0245335 -0.0162858 -0.00466105 0.98687 0.160628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 0.00113298 0.0674736 4.00329 0.0378921 0.104732 +EDGE_SE3:QUAT 1298 1299 4.27508 -0.185129 -0.00128738 0.00114929 -0.00489394 -0.0158481 0.999862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -3.13545e-05 -0.0389214 3.99991 0.000308529 3.99937 +EDGE_SE3:QUAT 289 1298 6.1603 0.476349 0.078477 0.00928791 0.00680155 -0.999375 0.0334146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 0.000191729 0.0372157 4.00129 0.0246618 0.004965 +EDGE_SE3:QUAT 290 1298 2.02492 0.580788 0.00857917 0.00483779 0.00425453 -0.999435 0.032995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.71811e-05 0.0193841 4.00033 0.0156982 0.0045104 +EDGE_SE3:QUAT 291 1298 -1.9183 0.745275 -0.0218045 -0.00420791 -0.000702137 0.99998 0.00470823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.37991e-05 0.0168321 4.00028 0.00296717 0.000161703 +EDGE_SE3:QUAT 292 1298 -6.03182 1.67132 -0.105023 -0.0139055 0.000630599 0.994872 0.100183 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99927 0.00042692 0.0564544 4.00304 0.00858579 0.0409693 +EDGE_SE3:QUAT 1299 1300 4.43781 -0.129506 -0.00805127 0.000794024 -0.00345744 -0.00888298 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -1.34726e-05 -0.0275727 3.99995 0.000122576 3.99987 +EDGE_SE3:QUAT 288 1299 6.22949 0.20253 0.0588741 0.00621482 0.00701542 -0.999919 0.00860453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000169683 0.0248633 4.00044 0.027634 0.000641605 +EDGE_SE3:QUAT 289 1299 1.88134 0.375826 0.00464228 0.0042707 0.00562114 -0.999825 0.0173343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.23759e-05 0.0170913 4.00019 0.0218776 0.00139464 +EDGE_SE3:QUAT 290 1299 -2.23663 0.489573 -0.0314744 8.27637e-05 0.0029193 -0.999845 0.0173858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.14262e-06 0.000331335 3.99997 0.0116568 0.00124307 +EDGE_SE3:QUAT 291 1299 -6.16761 0.963794 -0.0598024 0.000941512 0.000199879 0.999786 0.0206446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.17991e-06 -0.00376844 4.00001 -0.000954101 0.00170858 +EDGE_SE3:QUAT 1300 1301 4.30512 -0.116485 0.022315 -0.00357259 0.00493922 -0.00651316 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -7.37059e-05 0.0392346 3.9999 -0.000129565 4.00022 +EDGE_SE3:QUAT 287 1300 6.30135 0.0741105 -0.0152974 0.000861781 -0.00342568 0.999941 0.0102341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.25668e-05 -0.00344776 3.99997 0.0136286 0.000468363 +EDGE_SE3:QUAT 288 1300 1.79968 0.259096 -0.00365685 -0.00267422 -0.00654629 0.999975 0.000108821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.00073e-05 0.0106975 3.99994 0.026188 0.000200109 +EDGE_SE3:QUAT 289 1300 -2.5109 0.348811 -0.0433579 0.000602309 0.00503074 -0.99995 0.00859435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.377e-05 0.00240963 3.99991 0.0200776 0.000397691 +EDGE_SE3:QUAT 290 1300 -6.65379 0.475134 -0.04084 -0.00351401 0.00260059 -0.999957 0.00823197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -3.85142e-05 -0.0140575 4.00017 0.0106327 0.000348732 +EDGE_SE3:QUAT 1301 1302 4.21707 -0.102771 0.0415821 -0.000702186 -6.76693e-05 -0.00119024 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.94625e-07 -0.000551382 4 3.30046e-07 3.99999 +EDGE_SE3:QUAT 286 1301 6.31785 0.162574 0.00590056 -0.00521667 -0.00559111 0.999723 0.0222698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000124751 0.0208826 4.00028 0.0232686 0.00222825 +EDGE_SE3:QUAT 287 1301 2.01973 0.285805 0.00857322 -0.00417806 -0.00748738 0.999823 0.0167443 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000124094 0.0167203 4.00003 0.0304899 0.00142386 +EDGE_SE3:QUAT 288 1301 -2.47188 0.37191 -0.00886701 -0.00746621 -0.0105923 0.999893 0.006847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000319284 0.0298713 4.00042 0.0427838 0.000868157 +EDGE_SE3:QUAT 289 1301 -6.79417 0.386814 -0.0309811 0.00562047 0.0089055 -0.999942 0.00235136 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000199962 0.0224843 4.00019 0.0355206 0.000463902 +EDGE_SE3:QUAT 1302 1303 4.13516 -0.0825121 0.0102226 0.00173938 -0.00259953 0.00526835 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -1.73529e-05 -0.0209058 3.99997 -5.48847e-05 4 +EDGE_SE3:QUAT 285 1302 6.35096 0.345879 0.0408231 -0.00698645 -0.00745054 0.999646 0.0245607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000224174 0.0279723 4.0005 0.0311361 0.0028511 +EDGE_SE3:QUAT 286 1302 2.12009 0.462518 0.0062231 -0.00502244 -0.00634369 0.99969 0.0235619 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000133025 0.020107 4.00021 0.0262886 0.00249463 +EDGE_SE3:QUAT 287 1302 -2.18117 0.52271 0.0255288 -0.00404655 -0.00788377 0.999795 0.0181936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000125055 0.0161953 3.99999 0.0320994 0.00164728 +EDGE_SE3:QUAT 288 1302 -6.67024 0.532297 -0.0268474 -0.00743608 -0.011033 0.999877 0.00826901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000330894 0.0297522 4.00037 0.0446266 0.000992647 +EDGE_SE3:QUAT 1303 1304 4.19205 -0.0605684 -0.0268907 0.00205164 0.00554389 0.011473 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 5.34951e-05 0.0440643 3.99988 0.000253796 3.99996 +EDGE_SE3:QUAT 284 1303 6.50842 0.51753 0.0208515 0.00146515 -0.00723405 0.99976 0.0206109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.96563e-05 -0.00586532 3.99984 0.0286637 0.00191334 +EDGE_SE3:QUAT 285 1303 2.23359 0.631057 0.00208728 -0.00454326 -0.00576581 0.999788 0.0192587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000108602 0.0181837 4.00017 0.0237437 0.00170726 +EDGE_SE3:QUAT 286 1303 -1.9953 0.732779 -0.0191926 -0.00271727 -0.00460905 0.999819 0.0182628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.99667e-05 0.0108746 4.00002 0.0188182 0.00145225 +EDGE_SE3:QUAT 287 1303 -6.28811 0.766386 0.00529337 -0.00160595 -0.0062485 0.999893 0.0131561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.67339e-05 0.00642569 3.99988 0.025152 0.000860845 +EDGE_SE3:QUAT 1304 1305 4.32801 -0.0417177 0.00253848 -0.00116952 0.00615824 0.0129009 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -1.71479e-05 0.0494412 3.99985 0.000318337 3.99995 +EDGE_SE3:QUAT 283 1304 6.53132 0.645883 0.00345526 0.00165552 -0.00431922 0.999934 0.0105233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.94294e-05 -0.00662339 3.99997 0.0171329 0.000527323 +EDGE_SE3:QUAT 284 1304 2.32148 0.739675 0.0120546 -0.00403754 -0.00514172 0.999937 0.00907534 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.45754e-05 0.0161527 4.00015 0.0208573 0.000503439 +EDGE_SE3:QUAT 285 1304 -1.92256 0.844404 -0.0540229 -0.0103063 -0.00350821 0.999909 0.00798386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99958 0.000164263 0.041228 4.00164 0.0146974 0.000733948 +EDGE_SE3:QUAT 286 1304 -6.15242 0.942063 -0.0587078 -0.00830349 -0.00232019 0.999938 0.00711128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 8.85371e-05 0.0332157 4.00108 0.00975563 0.000501919 +EDGE_SE3:QUAT 1305 1306 4.30152 -0.0650826 0.0407779 0.00671822 0.00203539 0.0127169 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 5.12286e-05 0.0152532 3.99999 9.5411e-05 3.99941 +EDGE_SE3:QUAT 282 1305 6.58259 0.652172 0.006346 0.0025423 0.0103286 -0.999943 0.000992629 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000105712 0.0101708 3.99968 0.0412934 0.000456118 +EDGE_SE3:QUAT 283 1305 2.22607 0.777049 0.0269808 0.00445502 0.00535 -0.999972 0.00263012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.46976e-05 0.0178208 4.00021 0.0213079 0.000220565 +EDGE_SE3:QUAT 284 1305 -1.99137 0.86847 -0.0232441 0.0103685 0.00622558 -0.99992 0.00373035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99957 0.000250042 0.0414749 4.00158 0.0246062 0.000637034 +EDGE_SE3:QUAT 285 1305 -6.22228 0.95241 -0.137145 0.0165184 0.00448024 -0.999839 0.00529823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9989 0.000263131 0.066069 4.00431 0.0172451 0.00127812 +EDGE_SE3:QUAT 1306 1307 4.29674 -0.0457047 0.0362866 -0.0013692 -0.00743648 0.00981211 0.999923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00087 5.35735e-05 -0.0593333 3.99978 -0.000292793 4.00049 +EDGE_SE3:QUAT 281 1306 6.67332 0.611668 0.0868566 0.0124406 0.00457307 -0.999834 0.0125051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99937 0.000183111 0.0497712 4.00243 0.017055 0.00131767 +EDGE_SE3:QUAT 282 1306 2.29247 0.713468 0.0334496 0.00478969 0.00338591 -0.999887 0.0138117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 5.8355e-05 0.0191644 4.00033 0.0130096 0.000897207 +EDGE_SE3:QUAT 283 1306 -2.05149 0.817398 0.0302182 0.00652044 -0.00132554 -0.999862 0.0152161 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -4.97738e-05 0.0260903 4.00067 -0.00609411 0.00110563 +EDGE_SE3:QUAT 284 1306 -6.24742 0.899188 -0.0649432 0.0125031 -0.000501233 -0.999785 0.0165154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 -8.69588e-05 0.0500289 4.00249 -0.00365859 0.00172037 +EDGE_SE3:QUAT 1307 1308 4.15563 -0.061551 0.0285268 -0.00168569 -0.00574114 0.00442193 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 4.21144e-05 -0.0458434 3.99987 -0.000102656 4.00045 +EDGE_SE3:QUAT 280 1307 6.7092 0.407841 0.0657746 0.0104558 0.00363593 -0.999784 0.0176056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 0.000107215 0.0418408 4.00173 0.0130679 0.00172037 +EDGE_SE3:QUAT 281 1307 2.38373 0.536972 0.0141956 0.00486625 0.00581796 -0.999728 0.0220674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.00010583 0.0194803 4.00027 0.0223876 0.00216815 +EDGE_SE3:QUAT 282 1307 -1.95986 0.637753 0.0292221 -0.00256096 0.00463325 -0.9997 0.0239122 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.66939e-05 -0.0102525 4.00001 0.0189965 0.00240373 +EDGE_SE3:QUAT 283 1307 -6.30768 0.735475 0.00611936 -0.000868034 6.94448e-05 -0.999678 0.0253485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.95526e-07 -0.00347547 4.00001 0.000453249 0.00257326 +EDGE_SE3:QUAT 1308 1309 4.36673 -0.0743382 0.00200614 -0.00443135 0.00249556 -0.00194655 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.42194e-05 0.0198607 3.99998 -1.99544e-05 4.00008 +EDGE_SE3:QUAT 279 1308 6.98969 0.160269 0.0498522 0.00472517 0.00334545 -0.999889 0.0137263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 5.69344e-05 0.0189061 4.00032 0.0128583 0.000884363 +EDGE_SE3:QUAT 280 1308 2.55245 0.323411 0.0119835 0.00467032 0.0051502 -0.999727 0.0223231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.85229e-05 0.0186961 4.00027 0.0197437 0.0021782 +EDGE_SE3:QUAT 281 1308 -1.76058 0.419834 0.00458029 -0.000754032 0.00745682 -0.999592 0.027578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.03653e-05 -0.00301848 3.99978 0.029936 0.00326868 +EDGE_SE3:QUAT 282 1308 -6.09582 0.504762 0.0777434 -0.00826596 0.00628882 -0.999524 0.0290329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000243691 -0.033106 4.00086 0.0270297 0.00382861 +EDGE_SE3:QUAT 1309 1310 4.15199 -0.164637 0.0336918 -0.00364572 -2.80226e-06 -0.0324943 0.999465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.47887e-06 -0.00144295 4 3.11409e-05 3.99578 +EDGE_SE3:QUAT 278 1309 6.93393 0.148733 0.00169472 0.00336695 0.00433914 -0.999775 0.0204793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.55659e-05 0.0134768 4.00012 0.0167879 0.00179353 +EDGE_SE3:QUAT 279 1309 2.61042 0.112336 0.00738482 0.0071774 0.00775734 -0.999879 0.0113712 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000213804 0.0287169 4.00061 0.0303744 0.000954044 +EDGE_SE3:QUAT 280 1309 -1.79024 0.196691 -0.0362758 0.00724169 0.00991106 -0.999712 0.020631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000275547 0.0289889 4.00052 0.0384173 0.00228179 +EDGE_SE3:QUAT 281 1309 -6.11767 0.261974 0.00900424 0.00164569 0.0122782 -0.9996 0.0254356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000108904 0.00659254 3.99947 0.0486962 0.00319204 +EDGE_SE3:QUAT 1310 1311 4.04566 -0.35011 0.0210602 -0.00419825 0.006998 -0.0850477 0.996343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 -0.000191122 0.051119 3.99985 -0.00210968 3.97172 +EDGE_SE3:QUAT 277 1310 6.89002 0.779273 -0.0892926 -0.0071333 0.00385265 -0.998327 0.0572538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.00016706 -0.028668 4.00067 0.0185458 0.0134043 +EDGE_SE3:QUAT 278 1310 2.77996 0.133997 0.0064476 -0.00330666 -0.00835256 0.999887 0.0120736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000106652 0.0132307 3.99988 0.0337181 0.000911132 +EDGE_SE3:QUAT 279 1310 -1.51127 0.171619 -0.0128647 -0.00701333 -0.011804 0.999686 0.020962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000330326 0.0280766 4.00015 0.0483483 0.00253934 +EDGE_SE3:QUAT 280 1310 -5.93176 0.194849 -0.0531746 -0.00686434 -0.0137969 0.999808 0.0121166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 0.000373277 0.0274706 3.99994 0.0558407 0.00155554 +EDGE_SE3:QUAT 1311 1312 4.09621 -0.560096 -0.021428 0.000438467 0.00886457 -0.133261 0.991041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00121 -0.000231862 0.0697473 3.99972 -0.00462339 3.93018 +EDGE_SE3:QUAT 276 1311 6.67186 2.10484 -0.00785017 -0.00433276 0.00779748 -0.991889 0.126792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.91388e-05 -0.0176184 3.99987 0.0342682 0.0646808 +EDGE_SE3:QUAT 277 1311 2.82517 0.668446 -0.00166541 0.000505131 -0.00765284 0.999578 0.0280323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.81826e-05 -0.00202452 3.99978 0.0304373 0.00337607 +EDGE_SE3:QUAT 278 1311 -1.23921 0.57589 0.0154614 -0.009487 -0.0126488 0.995166 0.0969307 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000495629 0.0383983 4.00026 0.0567124 0.0387642 +EDGE_SE3:QUAT 279 1311 -5.54039 0.688187 -0.0371882 -0.0129972 -0.0167322 0.994138 0.106027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 0.00091127 0.0527272 4.00051 0.0759912 0.047125 +EDGE_SE3:QUAT 1312 1313 4.23722 -0.771716 0.0111117 0.00397892 -0.00327549 -0.16894 0.985613 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.15678e-05 -0.0171768 3.99999 0.00119227 3.88591 +EDGE_SE3:QUAT 275 1312 5.96739 3.05313 0.077333 0.0102218 0.0113888 -0.983672 0.179318 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99934 -2.94026e-05 0.0433303 4.00207 0.0277608 0.129312 +EDGE_SE3:QUAT 276 1312 2.57257 1.59604 0.00815559 -0.00348569 -0.00774491 0.99994 0.00694436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.0001066 0.0139449 3.99995 0.0311706 0.000484426 +EDGE_SE3:QUAT 277 1312 -1.22514 1.44748 -0.0105212 -0.00725396 -0.00671074 0.986822 0.161505 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000258478 0.0299064 4.00027 0.0342419 0.104863 +EDGE_SE3:QUAT 278 1312 -5.16635 1.90951 -0.0610666 -0.0163798 -0.0123735 0.973044 0.229705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.00128555 0.0693399 4.00125 0.0716492 0.213631 +EDGE_SE3:QUAT 1313 1314 4.18653 -0.804951 0.0181659 -0.000154036 0.00251094 -0.174986 0.984568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -2.57897e-05 0.0188555 3.99998 -0.00161289 3.87761 +EDGE_SE3:QUAT 274 1313 4.86022 3.36356 -0.00101389 0.00211974 0.00730262 -0.981008 0.19382 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 7.5566e-05 0.00936879 4.00005 0.0233414 0.150431 +EDGE_SE3:QUAT 275 1313 1.754 2.28081 0.00415793 0.00543158 0.00843134 -0.999883 0.0115818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000181228 0.0217326 4.00021 0.0332153 0.000930466 +EDGE_SE3:QUAT 276 1313 -1.62845 2.41303 0.00935749 0.00118673 -0.00387889 0.984449 0.175621 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.22472e-05 -0.00512952 4.00001 0.0127165 0.12342 +EDGE_SE3:QUAT 277 1313 -4.95927 3.52274 -0.0357775 -0.0021223 -0.00431239 0.945429 0.325792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.67494e-05 0.00853683 3.99992 0.0177905 0.424669 +EDGE_SE3:QUAT 1314 1315 4.17714 -0.729813 0.00565795 0.00228544 0.00136276 -0.143207 0.989689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 7.74669e-06 0.0144423 3.99999 -0.00111958 3.91802 +EDGE_SE3:QUAT 273 1314 4.03642 3.04622 0.00698725 0.00173912 0.00732639 -0.985634 0.168726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.00864e-05 0.00752911 3.99997 0.0249608 0.11405 +EDGE_SE3:QUAT 274 1314 0.697517 2.52403 -0.00131456 0.00330423 0.00825574 -0.999779 0.0190728 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000113874 0.0132259 3.99993 0.03249 0.00176283 +EDGE_SE3:QUAT 275 1314 -2.41959 2.98111 -0.00565044 -0.00644093 -0.00935735 0.986399 0.163977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000194297 0.0264558 3.99988 0.0431614 0.108209 +EDGE_SE3:QUAT 276 1314 -5.25596 4.59463 0.050574 -0.000716355 -0.00341466 0.938727 0.344645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.90886e-05 0.00221053 3.99997 0.0115163 0.475161 +EDGE_SE3:QUAT 1315 1316 4.31125 -0.488837 0.00757137 0.00400862 -2.30355e-05 -0.0706152 0.997496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.53348e-06 0.0032026 4 -0.000153061 3.98006 +EDGE_SE3:QUAT 272 1315 3.74117 2.37515 0.00604857 0.00319409 0.00335171 -0.996566 0.0826716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 2.53908e-05 0.0129218 4.00016 0.0110809 0.0274114 +EDGE_SE3:QUAT 273 1315 -0.149814 2.32859 -0.00418054 0.00249283 0.00562222 -0.99965 0.0257326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.81246e-05 0.0099824 3.99999 0.0219394 0.00279402 +EDGE_SE3:QUAT 274 1315 -3.49324 3.07678 -0.0142152 -0.00342071 -0.00633972 0.992203 0.124422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.23053e-05 0.0139 3.99991 0.0277352 0.0621675 +EDGE_SE3:QUAT 1316 1317 4.00705 -0.139021 0.0100869 0.000749923 -0.00144915 -0.00843999 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -4.72955e-06 -0.0115161 3.99999 4.85277e-05 3.99975 +EDGE_SE3:QUAT 271 1316 3.43553 2.03483 -0.00269067 0.00309501 -0.00213996 -0.999913 0.0126142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -2.8866e-05 0.012383 4.00013 -0.00886916 0.000694483 +EDGE_SE3:QUAT 272 1316 -0.597051 2.14415 -0.0199773 0.00317973 -0.00018879 -0.999922 0.0121152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.33163e-06 0.0127216 4.00016 -0.00106308 0.000627866 +EDGE_SE3:QUAT 273 1316 -4.49681 2.60605 -0.0120851 -0.00247784 -0.00147299 0.998979 0.045077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.99691e-05 0.00994048 4.00008 0.00675399 0.00816393 +EDGE_SE3:QUAT 316 1316 1.61639 6.70546 0.153881 0.0125888 0.00189105 -0.492176 0.870403 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 -0.000192344 0.0723406 3.99968 -0.0231502 3.03234 +EDGE_SE3:QUAT 1247 1316 2.30383 6.8269 0.149529 0.0128533 0.000590074 -0.501691 0.864951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -6.72717e-05 0.0674654 3.99967 -0.0229701 2.99433 +EDGE_SE3:QUAT 1317 1318 4.06188 -0.0846746 0.00987483 -0.0014118 -0.000439404 0.00134589 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.46611e-06 -0.00349242 4 -2.35156e-06 4 +EDGE_SE3:QUAT 270 1317 3.4715 1.96324 0.00311804 0.00293884 -0.00164659 -0.999992 0.00191646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -1.9713e-05 0.0117554 4.00013 -0.00663166 6.02334e-05 +EDGE_SE3:QUAT 271 1317 -0.555452 2.08295 -0.0170907 0.00178094 -0.00287272 -0.999984 0.00445119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.05036e-05 0.00712405 4.00002 -0.0115539 0.000125314 +EDGE_SE3:QUAT 272 1317 -4.60541 2.18888 -0.0299983 0.00195979 -0.00116287 -0.999992 0.00330902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.384e-06 0.00783929 4.00006 -0.00470333 6.46927e-05 +EDGE_SE3:QUAT 316 1317 3.56712 3.20676 0.099497 0.0128021 0.000161509 -0.499459 0.866243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -1.5363e-05 0.0648199 3.99967 -0.0222895 3.00317 +EDGE_SE3:QUAT 317 1317 -1.81174 3.57007 0.0558812 0.00707953 0.00378155 -0.340085 0.94036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -9.20499e-05 0.0518294 3.99984 -0.0101121 3.53804 +EDGE_SE3:QUAT 318 1317 -6.9905 1.61511 -0.0464932 0.00829923 -0.00174924 -0.130975 0.991349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 1.4923e-05 -0.000739717 4 -0.000244214 3.93138 +EDGE_SE3:QUAT 1247 1317 4.17659 3.29926 0.0978728 0.0127392 -0.000876215 -0.508802 0.860789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 6.70007e-05 0.0598924 3.99967 -0.0218474 2.96533 +EDGE_SE3:QUAT 1248 1317 -1.7508 3.84831 0.0541034 0.0055868 0.0041606 -0.321168 0.946996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -0.000108995 0.0483268 3.99987 -0.00860725 3.58799 +EDGE_SE3:QUAT 1249 1317 -7.03584 2.26147 -0.0443403 0.00545853 -0.00154438 -0.140101 0.990121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -5.99734e-07 -0.00293584 4 -1.71657e-05 3.92149 +EDGE_SE3:QUAT 1318 1319 4.14237 -0.0740926 0.0150441 -0.00074704 0.00651032 0.0026249 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00068 -1.68044e-05 0.0521132 3.99983 6.7676e-05 4.00065 +EDGE_SE3:QUAT 269 1318 3.66988 1.92893 0.0170267 -0.00560032 -0.000544121 0.999984 0.000453258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 1.25345e-05 0.0224009 4.0005 0.00219717 0.000127483 +EDGE_SE3:QUAT 270 1318 -0.560647 2.03101 -0.00674662 0.00239346 -0.00023808 -0.999993 0.00283573 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.66782e-06 0.00957394 4.00009 -0.00100663 5.53341e-05 +EDGE_SE3:QUAT 271 1318 -4.61148 2.12796 -0.0212757 0.00134423 -0.00163263 -0.999982 0.0055391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.89647e-06 0.00537716 4.00002 -0.00658966 0.000140811 +EDGE_SE3:QUAT 316 1318 5.52246 -0.338069 0.0548313 0.0114426 0.000527356 -0.498404 0.866869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -4.69413e-05 0.0598612 3.99974 -0.0202384 3.00724 +EDGE_SE3:QUAT 317 1318 1.25726 0.906343 0.0150113 0.00556408 0.00382988 -0.338918 0.940792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 -0.000105776 0.0464161 3.99989 -0.00880874 3.54108 +EDGE_SE3:QUAT 318 1318 -3.1077 0.483875 -0.0340958 0.00698089 -0.00192551 -0.130009 0.991486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -3.82205e-06 -0.0042462 4 3.15918e-05 3.93239 +EDGE_SE3:QUAT 319 1318 -6.96298 -2.36156 -0.13145 0.0062059 -0.00877196 0.145582 0.989288 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00139 7.22122e-05 -0.0786697 3.99962 -0.00592595 3.91677 +EDGE_SE3:QUAT 1247 1318 6.0776 -0.329603 0.0648513 0.0114257 -0.000660267 -0.507538 0.861554 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 4.53268e-05 0.0542644 3.99974 -0.0196336 2.97032 +EDGE_SE3:QUAT 1248 1318 1.43252 1.3062 0.0168057 0.00417009 0.0041655 -0.320122 0.947358 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0004 -0.000116905 0.0432643 3.99991 -0.00747936 3.59056 +EDGE_SE3:QUAT 1249 1318 -3.18949 1.063 -0.0235852 0.0043652 -0.00157447 -0.139002 0.990281 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -7.77254e-06 -0.0050447 4 0.000173446 3.92272 +EDGE_SE3:QUAT 1319 1320 4.11105 -0.0891463 -0.00711485 0.00295323 0.000383059 0.000404589 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.49816e-06 0.00305009 4 6.26373e-07 4 +EDGE_SE3:QUAT 268 1319 3.74242 1.88735 -0.0049875 0.00148427 -0.00431566 0.999988 0.00186274 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.58e-05 -0.00593728 3.99996 0.0172404 9.7001e-05 +EDGE_SE3:QUAT 269 1319 -0.468967 2.00705 -0.0215546 0.0122896 0.00155831 -0.999922 0.00187506 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9994 6.99963e-05 0.0491549 4.00241 0.00605384 0.000627362 +EDGE_SE3:QUAT 270 1319 -4.72082 2.08905 -0.011953 0.00905493 0.000584723 -0.999943 0.0056309 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 1.01232e-05 0.03622 4.00131 0.00193164 0.000455769 +EDGE_SE3:QUAT 317 1319 4.41595 -1.80007 -0.0175098 0.00717023 0.0103064 -0.336424 0.941627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00208 -0.000793721 0.0956694 3.99964 -0.016852 3.54956 +EDGE_SE3:QUAT 318 1319 0.858595 -0.660529 -0.00672444 0.00686412 0.00464848 -0.126995 0.991869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 7.57718e-05 0.0466432 3.99985 -0.00315955 3.93603 +EDGE_SE3:QUAT 319 1319 -2.95316 -1.24259 -0.0345276 0.00427963 -0.00255758 0.148233 0.98894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.59856e-05 -0.0272916 3.99995 -0.00219296 3.91229 +EDGE_SE3:QUAT 320 1319 -6.0395 -3.61222 -0.0814602 0.00507958 -0.00631006 0.399488 0.916703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 0.00039512 -0.0606647 3.9999 -0.0128133 3.36256 +EDGE_SE3:QUAT 1248 1319 4.67449 -1.25707 -0.0176964 0.0054839 0.0106427 -0.31755 0.948166 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.002 -0.000770713 0.09213 3.99967 -0.0149978 3.59877 +EDGE_SE3:QUAT 1249 1319 0.781158 -0.167455 -0.000495286 0.00428377 0.00483496 -0.13624 0.990655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 3.21763e-06 0.0445287 3.99987 -0.00316536 3.92625 +EDGE_SE3:QUAT 1250 1319 -3.37917 -0.302158 -0.0131326 0.00139799 -0.000224261 -0.026658 0.999644 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.56476e-07 -0.00134517 4 1.59354e-05 3.99716 +EDGE_SE3:QUAT 1251 1319 -7.38343 -0.536939 -0.0668985 0.00149819 -0.00342571 0.00732205 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -1.85844e-05 -0.0275362 3.99995 -0.000100556 3.99998 +EDGE_SE3:QUAT 1320 1321 4.17228 -0.0890464 0.0106899 -0.00154177 0.00242271 0.000189351 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.49191e-05 0.0193855 3.99998 1.6183e-06 4.00009 +EDGE_SE3:QUAT 267 1320 3.86376 1.91809 -0.00215521 -0.00140971 0.0021832 0.999986 0.00465438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.22621e-05 0.00563905 4.00001 -0.00867992 0.000113439 +EDGE_SE3:QUAT 268 1320 -0.356062 2.00847 0.000743337 0.00112327 -0.00133278 0.999997 0.00170782 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.96066e-06 -0.00449311 4.00001 0.00531578 2.3778e-05 +EDGE_SE3:QUAT 269 1320 -4.57713 2.09624 -0.13054 0.0127316 -0.00126874 -0.999915 0.0023396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99935 -7.38315e-05 0.0509227 4.00259 -0.00531799 0.000677348 +EDGE_SE3:QUAT 318 1320 4.81752 -1.79501 -0.0608415 0.00979333 0.00462015 -0.126783 0.991871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 0.000162512 0.0508155 3.99982 -0.00350955 3.93635 +EDGE_SE3:QUAT 319 1320 0.988956 -0.125278 -0.0138111 0.00708779 -0.00169336 0.148756 0.988847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -7.54532e-05 -0.0255649 3.99995 -0.00220244 3.91165 +EDGE_SE3:QUAT 320 1320 -3.17593 -0.677354 -0.0180588 0.00785306 -0.00465337 0.400041 0.916452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00072 0.000252956 -0.0623476 3.99982 -0.0142762 3.36084 +EDGE_SE3:QUAT 321 1320 -6.63219 -2.76575 -0.00370747 0.0103732 -0.00223248 0.58592 0.810299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00065 0.000424844 -0.0657628 3.9999 -0.0247279 2.62787 +EDGE_SE3:QUAT 1249 1320 4.70359 -1.36364 -0.0550144 0.00712505 0.00490291 -0.13565 0.990719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 7.4342e-05 0.0496058 3.99983 -0.00359692 3.92701 +EDGE_SE3:QUAT 1250 1320 0.719165 -0.612078 -0.014625 0.00467663 0.000124873 -0.0262187 0.999645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.87353e-06 0.0024686 4 -3.87787e-05 3.99725 +EDGE_SE3:QUAT 1251 1320 -3.28777 -0.567957 -0.0379921 0.00442495 -0.00297214 0.00791229 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -5.21201e-05 -0.0241951 3.99996 -9.53146e-05 3.9999 +EDGE_SE3:QUAT 1252 1320 -7.42155 -0.495143 -0.0327135 0.00255524 -0.000774673 0.0101456 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.28844e-06 -0.00650745 4 -3.34959e-05 3.9996 +EDGE_SE3:QUAT 1321 1322 4.14256 -0.0971924 0.0218536 0.000459184 -0.00152591 0.000999077 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.74859e-06 -0.0122129 3.99999 -6.07619e-06 4.00003 +EDGE_SE3:QUAT 266 1321 3.79233 1.99339 0.0203396 0.00577219 -0.000617402 -0.99998 0.00236264 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -1.61428e-05 0.0230886 4.00053 -0.00257915 0.000157267 +EDGE_SE3:QUAT 267 1321 -0.310299 2.03769 -0.00087563 -0.00367266 0.000694119 0.999982 0.00467377 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -8.70039e-06 0.014691 4.00021 -0.0026392 0.000143076 +EDGE_SE3:QUAT 268 1321 -4.5115 2.10781 0.0193869 -0.00130937 -0.0027156 0.999994 0.00143277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.4197e-05 0.00523756 4 0.0108774 4.46488e-05 +EDGE_SE3:QUAT 319 1321 4.98766 1.00699 0.0222815 0.00528374 0.000413804 0.148717 0.988866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.36339e-05 -0.00608908 3.99999 -0.000689174 3.91154 +EDGE_SE3:QUAT 320 1321 -0.288348 2.29346 0.0502091 0.00503814 -0.00325318 0.400007 0.916493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000121871 -0.0416438 3.99992 -0.0094499 3.36041 +EDGE_SE3:QUAT 321 1321 -5.25315 1.14454 0.0751043 0.00765566 -0.00119603 0.586312 0.810049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 0.000187921 -0.0466113 3.99993 -0.017932 2.6255 +EDGE_SE3:QUAT 812 1321 -3.23031 6.52584 0.148081 0.00778614 0.00723078 -0.335133 0.942111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00125 -0.000386521 0.0773729 3.99972 -0.0141064 3.55224 +EDGE_SE3:QUAT 1250 1321 4.85475 -0.915934 -0.00624266 0.0031254 0.00259391 -0.0261309 0.99965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.9898e-05 0.0217099 3.99997 -0.000287303 3.99739 +EDGE_SE3:QUAT 1251 1321 0.890978 -0.592657 -0.00369099 0.00297048 -0.00068196 0.00775423 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -8.5558e-06 -0.00573152 4 -2.25425e-05 3.99977 +EDGE_SE3:QUAT 1252 1321 -3.27281 -0.489751 -0.0113695 0.00119878 0.00176375 0.00994703 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 9.07255e-06 0.013965 3.99999 6.93045e-05 3.99965 +EDGE_SE3:QUAT 1322 1323 4.10995 -0.0843843 0.017451 -0.000813309 -0.00136763 0.00126061 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.49913e-06 -0.0109287 3.99999 -6.92243e-06 4.00002 +EDGE_SE3:QUAT 265 1322 3.92208 1.99429 0.0164306 0.00447523 0.000861707 -0.99989 0.0141143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 8.68189e-06 0.0179061 4.00032 0.0029402 0.00087919 +EDGE_SE3:QUAT 266 1322 -0.347618 2.05937 -0.00449478 0.00417433 -0.00118935 -0.999985 0.00339127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -2.12401e-05 0.0166975 4.00027 -0.00487099 0.000121638 +EDGE_SE3:QUAT 267 1322 -4.4331 2.19096 -0.0109618 -0.00226779 0.000884694 0.999991 0.0034333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.62199e-06 0.00907131 4.00008 -0.00347648 7.07442e-05 +EDGE_SE3:QUAT 320 1322 2.57735 5.24725 0.114011 0.00622049 -0.00456739 0.401094 0.916005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 0.000235758 -0.0548244 3.99988 -0.0123038 3.35725 +EDGE_SE3:QUAT 321 1322 -3.87276 5.03938 0.141936 0.00898656 -0.00208864 0.586998 0.809536 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00051 0.000339252 -0.0576375 3.99993 -0.0215806 2.62256 +EDGE_SE3:QUAT 811 1322 5.83912 2.5028 0.127789 0.012291 0.00124364 -0.540718 0.841113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00061 -0.000244651 0.0701458 3.99973 -0.025297 2.83171 +EDGE_SE3:QUAT 812 1322 -0.0688573 3.82918 0.0887151 0.00760147 0.00551523 -0.334461 0.942363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00083 -0.00021409 0.0651771 3.99978 -0.0121364 3.5536 +EDGE_SE3:QUAT 813 1322 -5.90395 2.29112 0.0467173 0.0080308 0.00316466 -0.090995 0.995814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000111984 0.0337238 3.99992 -0.00165967 3.96716 +EDGE_SE3:QUAT 1251 1322 5.03865 -0.633585 0.0201068 0.0032224 -0.00227415 0.00902553 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -2.89056e-05 -0.01854 3.99998 -8.37807e-05 3.99976 +EDGE_SE3:QUAT 1252 1322 0.867692 -0.503694 -0.00571091 0.0014243 0.000115194 0.0110105 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.79923e-07 0.000733213 4 3.69119e-06 3.99952 +EDGE_SE3:QUAT 1253 1322 -3.36688 -0.40604 -0.0148016 0.00090165 0.000350434 0.0092698 0.999957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.22919e-06 0.00270282 4 1.23743e-05 3.99966 +EDGE_SE3:QUAT 1254 1322 -7.48769 -0.274801 -0.016477 -6.87047e-05 0.00163487 0.00715297 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 9.59373e-09 0.013084 3.99999 4.67974e-05 3.99984 +EDGE_SE3:QUAT 1323 1324 4.08645 -0.0881598 0.0161695 0.00171766 -0.000133559 0.00154181 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.53328e-07 -0.00110024 4 -8.55576e-07 3.99999 +EDGE_SE3:QUAT 264 1323 4.03603 1.8985 0.0217741 0.00451172 0.00384231 -0.999667 0.0251054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 5.93672e-05 0.0180645 4.00029 0.014441 0.00265493 +EDGE_SE3:QUAT 265 1323 -0.177256 1.96197 -0.00463293 0.00282991 0.00173292 -0.999877 0.0153305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.6967e-05 0.0113237 4.00012 0.00658091 0.000982986 +EDGE_SE3:QUAT 266 1323 -4.44048 2.12582 -0.0235081 0.00262696 -0.00040423 -0.999985 0.0048252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.03925e-06 0.0105082 4.00011 -0.0017183 0.000121474 +EDGE_SE3:QUAT 812 1323 3.04863 1.17886 0.0368756 0.0061064 0.00457543 -0.333232 0.942814 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 -0.000147118 0.0532974 3.99985 -0.00985771 3.55653 +EDGE_SE3:QUAT 813 1323 -1.88342 1.46257 0.0288831 0.00670513 0.00182701 -0.0902427 0.995896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 6.68206e-05 0.021659 3.99996 -0.00108281 3.96754 +EDGE_SE3:QUAT 814 1323 -6.32586 -0.907717 -0.059618 0.00518465 -0.00392657 0.189185 0.98192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -5.25945e-06 -0.0412338 3.99989 -0.00421456 3.85726 +EDGE_SE3:QUAT 1252 1323 4.98602 -0.494317 0.00808892 0.000608399 -0.00152149 0.0121633 0.999925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.05445e-06 -0.0122581 3.99999 -7.46917e-05 3.99945 +EDGE_SE3:QUAT 1253 1323 0.714944 -0.403127 -0.00515366 0.000117383 -0.00114103 0.0105653 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.05903e-07 -0.00914162 3.99999 -4.83123e-05 3.99957 +EDGE_SE3:QUAT 1254 1323 -3.38933 -0.301206 -0.0143812 -0.000987088 0.000211837 0.00832502 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.91386e-07 0.00179313 4 7.59932e-06 3.99972 +EDGE_SE3:QUAT 1255 1323 -7.4089 -0.191858 -0.0531872 0.000272919 -0.00151986 0.00591351 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.33402e-06 -0.0121777 3.99999 -3.60107e-05 3.9999 +EDGE_SE3:QUAT 1324 1325 4.33537 -0.0947048 0.0174326 -2.15444e-05 0.000591255 0.00216832 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.27651e-08 0.00473057 4 5.12872e-06 3.99999 +EDGE_SE3:QUAT 263 1324 4.25888 1.71649 0.00816247 0.00335813 2.56173e-05 -0.999472 0.0323202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -8.39256e-06 0.0134535 4.00018 -0.000765237 0.00422383 +EDGE_SE3:QUAT 264 1324 -0.0218445 1.77779 -0.00269925 0.00437806 0.00235322 -0.999636 0.0265178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 2.97451e-05 0.017531 4.0003 0.0084691 0.00290761 +EDGE_SE3:QUAT 265 1324 -4.25273 1.93741 -0.00808897 0.00292713 -5.46061e-05 -0.999858 0.0166202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.05229e-06 0.0117133 4.00014 -0.000607395 0.00113933 +EDGE_SE3:QUAT 812 1324 6.16173 -1.45004 -0.000658263 0.00767511 0.00382955 -0.332154 0.943186 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -7.85827e-05 0.0540579 3.99982 -0.010352 3.55942 +EDGE_SE3:QUAT 813 1324 2.11112 0.645241 0.0247499 0.00855226 0.00154373 -0.0884506 0.996043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 9.12017e-05 0.0212341 3.99996 -0.00106959 3.96882 +EDGE_SE3:QUAT 814 1324 -2.51276 0.52395 -0.00451288 0.0066595 -0.00373513 0.190296 0.981697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -4.11171e-05 -0.0431157 3.99987 -0.00452831 3.85561 +EDGE_SE3:QUAT 815 1324 -6.41017 -1.97534 -0.00766463 0.00905183 -0.00241841 0.452136 0.8919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00045 0.000133238 -0.0561561 3.99982 -0.0157871 3.18307 +EDGE_SE3:QUAT 1253 1324 4.79657 -0.408212 0.0184673 0.00166596 -0.00129302 0.0119289 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -8.38318e-06 -0.0105804 3.99999 -6.35078e-05 3.99946 +EDGE_SE3:QUAT 1254 1324 0.688725 -0.332687 -0.00335221 0.000493894 2.60546e-05 0.0101129 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.18278e-08 0.000148473 4 6.49675e-07 3.99959 +EDGE_SE3:QUAT 1255 1324 -3.33743 -0.232962 -0.0276133 0.00190749 -0.00165476 0.00765196 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.23342e-05 -0.0134121 3.99999 -5.14099e-05 3.99981 +EDGE_SE3:QUAT 1256 1324 -7.30975 -0.1104 -0.0397745 0.00198378 -0.00072439 0.00464468 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.83387e-06 -0.00590548 4 -1.37743e-05 3.99992 +EDGE_SE3:QUAT 1325 1326 4.2451 -0.0863959 0.0225609 -0.00159996 -0.00089633 0.0018825 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.73383e-06 -0.00713445 4 -6.73462e-06 4 +EDGE_SE3:QUAT 262 1325 4.41803 1.46289 0.00488664 0.00466459 -0.00231151 -0.999209 0.0394292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -6.09289e-05 0.0187008 4.00031 -0.0106804 0.00633475 +EDGE_SE3:QUAT 263 1325 -0.0527557 1.53596 -0.00947499 0.00406106 0.000372058 -0.999391 0.034645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -7.71647e-06 0.0162735 4.00026 0.00035956 0.00486744 +EDGE_SE3:QUAT 264 1325 -4.34948 1.64933 -0.0278097 0.00534501 0.00264549 -0.999576 0.0285005 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 3.79239e-05 0.0214064 4.00045 0.0093442 0.00338561 +EDGE_SE3:QUAT 813 1325 6.35552 -0.214963 0.0187676 0.00838287 0.0022008 -0.0863016 0.996231 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000102071 0.0260473 3.99995 -0.00124421 3.97038 +EDGE_SE3:QUAT 814 1325 1.56067 2.06502 0.0579699 0.00660234 -0.00310548 0.192438 0.981282 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -4.97898e-05 -0.0383484 3.9999 -0.00413047 3.85223 +EDGE_SE3:QUAT 815 1325 -3.77753 1.44528 0.0590003 0.00870975 -0.00193555 0.45439 0.890758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 9.29044e-05 -0.0519064 3.99984 -0.0148785 3.17478 +EDGE_SE3:QUAT 1254 1325 5.02194 -0.337111 0.0150828 0.000547564 0.000636889 0.012067 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.48022e-06 0.00501472 4 3.00998e-05 3.99942 +EDGE_SE3:QUAT 1255 1325 1.00244 -0.268137 0.000600798 0.00186662 -0.000957939 0.00989463 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.19909e-06 -0.00788399 4 -3.93256e-05 3.99962 +EDGE_SE3:QUAT 1256 1325 -2.96994 -0.172038 -0.0169957 0.00205211 -6.38886e-05 0.00679664 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.52294e-07 -0.000678434 4 -2.49477e-06 3.99982 +EDGE_SE3:QUAT 1257 1325 -7.03284 -0.0757845 -0.0123288 0.00242403 0.00256781 0.00479623 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 2.54242e-05 0.0204025 3.99997 4.91984e-05 4.00001 +EDGE_SE3:QUAT 1326 1327 4.26232 -0.0890389 0.0118568 -0.0013951 -0.00203044 0.00100023 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.14145e-05 -0.016227 3.99998 -8.25068e-06 4.00006 +EDGE_SE3:QUAT 210 1326 1.70477 5.1019 0.109026 0.00885158 0.00734946 -0.443589 0.896157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00142 -0.000724999 0.0832953 3.99982 -0.0204023 3.21465 +EDGE_SE3:QUAT 211 1326 -5.43746 4.03391 0.0778093 0.0103884 0.00436344 -0.183683 0.982921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 0.000142895 0.0555429 3.99978 -0.00573775 3.8658 +EDGE_SE3:QUAT 261 1326 4.62887 1.07514 0.0261777 0.00539547 0.00340856 -0.999184 0.0398926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 4.76112e-05 0.0216349 4.00045 0.0118627 0.00651812 +EDGE_SE3:QUAT 262 1326 0.175077 1.20363 -0.00647438 0.00377272 -0.000798408 -0.999136 0.0413906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -2.56074e-05 0.0151291 4.00022 -0.00442742 0.00691496 +EDGE_SE3:QUAT 263 1326 -4.30585 1.32149 -0.0175645 0.00313441 0.00182869 -0.999324 0.0365734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.48104e-05 0.0125635 4.00015 0.00637478 0.00540015 +EDGE_SE3:QUAT 814 1326 5.51277 3.58602 0.115819 0.00548735 -0.00445355 0.194449 0.980887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 6.33729e-06 -0.0461127 3.99986 -0.00482786 3.84929 +EDGE_SE3:QUAT 815 1326 -1.20385 4.84707 0.131174 0.00784307 -0.00366661 0.455638 0.890123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 0.000248512 -0.0576485 3.99987 -0.0155028 3.17041 +EDGE_SE3:QUAT 1255 1326 5.26568 -0.271135 0.0370619 0.000443532 -0.00187088 0.011579 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.35797e-06 -0.0150258 3.99999 -8.70706e-05 3.99952 +EDGE_SE3:QUAT 1256 1326 1.27755 -0.189812 0.00519063 0.000218457 -0.000806818 0.00887425 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.68904e-07 -0.00647706 4 -2.87696e-05 3.9997 +EDGE_SE3:QUAT 1257 1326 -2.8048 -0.12096 -0.00496811 0.000547874 0.00195404 0.00685299 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 4.89078e-06 0.0155864 3.99998 5.3406e-05 3.99987 +EDGE_SE3:QUAT 1258 1326 -6.79887 -0.40824 -0.0322238 0.00367967 0.000844918 0.0393118 0.99922 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.57178e-06 0.0050095 4 8.703e-05 3.99382 +EDGE_SE3:QUAT 1327 1328 4.17618 -0.0825821 0.00753388 -0.00133382 0.00494257 0.000769875 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 -2.59383e-05 0.0395562 3.9999 1.44496e-05 4.00039 +EDGE_SE3:QUAT 210 1327 4.21637 1.64917 0.0321363 0.00681312 0.00604578 -0.442712 0.896618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00091 -0.000476071 0.0663507 3.99989 -0.0160916 3.21713 +EDGE_SE3:QUAT 211 1327 -1.481 2.39967 0.0449936 0.00873974 0.00270257 -0.182642 0.983137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000110772 0.0392773 3.99988 -0.00413223 3.86695 +EDGE_SE3:QUAT 212 1327 -6.49725 0.207507 -0.132135 0.00536556 -0.0103832 0.0881045 0.996043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00181 9.5171e-06 -0.0877784 3.99952 -0.00392533 3.97088 +EDGE_SE3:QUAT 260 1327 4.83399 0.656952 0.00958888 0.00303793 0.00570756 -0.999565 0.0287747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.95522e-05 0.0121683 4.00004 0.0220852 0.00347103 +EDGE_SE3:QUAT 261 1327 0.364538 0.828502 -0.00408927 0.0033259 0.0046811 -0.999148 0.0408602 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.69183e-05 0.0133397 4.00012 0.0175619 0.00680004 +EDGE_SE3:QUAT 262 1327 -4.08487 0.954849 -0.0179451 0.0017119 0.000480322 -0.999099 0.0424042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.99672e-07 0.00686633 4.00005 0.00133299 0.00720473 +EDGE_SE3:QUAT 1256 1327 5.52655 -0.214525 0.0299332 -0.00107182 -0.00294778 0.0099394 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.46007e-05 -0.0234515 3.99997 -0.000116562 3.99974 +EDGE_SE3:QUAT 1257 1327 1.47273 -0.1546 -0.00824033 -0.000693504 -6.96114e-05 0.00777833 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.63901e-07 -0.000492111 4 -1.82998e-06 3.99976 +EDGE_SE3:QUAT 1258 1327 -2.52627 -0.175447 -0.0188986 0.00233809 -0.00127434 0.0399685 0.999197 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.17963e-05 -0.0112905 3.99999 -0.000232836 3.99364 +EDGE_SE3:QUAT 1259 1327 -6.4197 -1.1287 -0.15247 0.00430329 -0.0109397 0.14508 0.98935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00205 0.000254955 -0.0921986 3.9995 -0.00679691 3.91793 +EDGE_SE3:QUAT 1328 1329 4.2631 -0.0956563 -0.00168812 0.00143755 0.00327893 0.000795174 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 1.90491e-05 0.0262186 3.99996 1.07942e-05 4.00017 +EDGE_SE3:QUAT 210 1328 6.68105 -1.69925 -0.0323548 0.00796141 0.0111464 -0.441888 0.896966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00229 -0.00136831 0.101153 3.99988 -0.0231886 3.22148 +EDGE_SE3:QUAT 211 1328 2.38059 0.813984 0.0149316 0.00809412 0.00775858 -0.181657 0.983298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -4.23013e-05 0.0762988 3.99963 -0.0073579 3.86945 +EDGE_SE3:QUAT 212 1328 -2.36709 0.860539 -0.0313049 0.00367612 -0.00562369 0.0888544 0.996022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 -1.51576e-05 -0.0483624 3.99985 -0.00219635 3.969 +EDGE_SE3:QUAT 213 1328 -6.65831 -1.68401 -0.0653451 0.0079987 -0.00814583 0.357699 0.933767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00153 0.000562377 -0.084507 3.9997 -0.0163204 3.48999 +EDGE_SE3:QUAT 259 1328 4.8311 0.319793 -0.00589854 -0.00110829 0.00633977 -0.999895 0.0129592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.4246e-05 -0.0044344 3.99985 0.0254629 0.000838801 +EDGE_SE3:QUAT 260 1328 0.644129 0.495663 -0.0128334 0.00797733 0.0071987 -0.999505 0.0295823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000193789 0.0319534 4.00089 0.0268547 0.00393636 +EDGE_SE3:QUAT 261 1328 -3.7929 0.571163 -0.0249341 0.00846562 0.00622194 -0.999059 0.0420777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000145717 0.0339557 4.00109 0.0219416 0.00749149 +EDGE_SE3:QUAT 1257 1328 5.66186 -0.169836 0.00236002 -0.00201382 0.00486808 0.00863116 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -3.45509e-05 0.039152 3.9999 0.000168144 4.00009 +EDGE_SE3:QUAT 1258 1328 1.64879 0.0779654 0.00241923 0.00099567 0.0036771 0.0412425 0.999142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 2.72674e-05 0.0288508 3.99995 0.000591433 3.9934 +EDGE_SE3:QUAT 1259 1328 -2.39381 -0.014607 -0.0443289 0.00234883 -0.00619864 0.145939 0.989271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 8.47068e-05 -0.052076 3.99984 -0.00386015 3.91548 +EDGE_SE3:QUAT 1260 1328 -6.43786 -1.65404 -0.0908025 0.00528705 -0.00888832 0.325365 0.945532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00146 0.000558137 -0.0793335 3.99975 -0.0133584 3.57812 +EDGE_SE3:QUAT 1329 1330 4.37576 -0.0983018 0.0139524 -0.000403703 -0.000220518 0.000243138 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.56061e-07 -0.00176296 4 -2.14745e-07 4 +EDGE_SE3:QUAT 211 1329 6.34429 -0.801025 -0.0613846 0.0103052 0.0105343 -0.180753 0.983418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00217 -0.000106284 0.102095 3.99935 -0.00974847 3.87191 +EDGE_SE3:QUAT 212 1329 1.86526 1.51716 0.0172856 0.00465183 -0.00235926 0.0899503 0.995933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -4.14348e-05 -0.0236398 3.99996 -0.0011342 3.96777 +EDGE_SE3:QUAT 213 1329 -3.41091 1.10234 0.0210421 0.00805019 -0.00472672 0.358594 0.933447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 0.000185054 -0.0624433 3.99979 -0.0127643 3.48661 +EDGE_SE3:QUAT 258 1329 4.99475 0.1175 0.00178158 -0.00219605 -0.00534324 0.999975 0.00402461 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.64709e-05 0.00878476 3.99996 0.0214431 0.000199036 +EDGE_SE3:QUAT 259 1329 0.571731 0.3017 0.00275193 0.00206862 0.00471712 -0.99989 0.0139107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.99577e-05 0.00827722 3.99999 0.0186295 0.000877943 +EDGE_SE3:QUAT 260 1329 -3.58187 0.345198 -0.0814326 0.0113796 0.00598698 -0.999447 0.0306641 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99945 0.000182488 0.0455822 4.00202 0.0211174 0.00439269 +EDGE_SE3:QUAT 1258 1329 5.91793 0.329822 -0.0322812 0.00211853 0.00685165 0.0419597 0.999094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0007 0.000102102 0.0536109 3.99982 0.00111912 3.99368 +EDGE_SE3:QUAT 1259 1329 1.73202 1.13066 0.0148164 0.00349138 -0.00271923 0.146892 0.989143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.30559e-05 -0.0271201 3.99995 -0.00212429 3.91387 +EDGE_SE3:QUAT 1260 1329 -3.00812 0.889771 -0.0042055 0.00550089 -0.00536276 0.326157 0.945285 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 0.000201208 -0.0562543 3.99985 -0.00993301 3.57528 +EDGE_SE3:QUAT 1261 1329 -7.05317 -0.904994 -0.00435821 0.00350194 -0.00231055 0.491836 0.870678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 9.8413e-05 -0.0295378 3.99998 -0.00824741 3.03261 +EDGE_SE3:QUAT 1330 1331 4.34551 -0.118715 0.0206071 -0.00143771 0.000221916 -0.0140168 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.05717e-06 0.001533 4 -1.01791e-05 3.99921 +EDGE_SE3:QUAT 212 1330 6.18171 2.19975 0.0595813 0.00470266 -0.00259743 0.0896341 0.99596 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -4.36208e-05 -0.0255609 3.99996 -0.0012164 3.96803 +EDGE_SE3:QUAT 213 1330 -0.108571 3.94966 0.104483 0.00809113 -0.00511688 0.358781 0.933373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0008 0.000220742 -0.0651511 3.99978 -0.0132279 3.48616 +EDGE_SE3:QUAT 214 1330 -5.76838 2.6906 0.0652378 0.00456167 -0.00303125 0.557645 0.830062 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 0.000212864 -0.0380703 4.00001 -0.0119774 2.75649 +EDGE_SE3:QUAT 257 1330 5.01673 0.0847562 0.00986003 -0.00313215 -0.00569799 0.999812 0.0182775 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.05708e-05 0.0125352 4.00001 0.0232315 0.00151053 +EDGE_SE3:QUAT 258 1330 0.627066 0.233871 0.00297115 -0.0020941 -0.0055531 0.999975 0.00380972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.59651e-05 0.00837694 3.99994 0.0222756 0.000199652 +EDGE_SE3:QUAT 259 1330 -3.81469 0.276381 -0.00406688 0.00188713 0.00519604 -0.999891 0.0137258 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.08937e-05 0.00755104 3.99996 0.0205674 0.000873623 +EDGE_SE3:QUAT 1259 1330 5.94697 2.29793 0.0530212 0.00305723 -0.00300798 0.146734 0.989167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -3.69449e-06 -0.0285979 3.99995 -0.0022098 3.91408 +EDGE_SE3:QUAT 1260 1330 0.485842 3.49634 0.0724297 0.0055083 -0.00584698 0.326036 0.945323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00076 0.000241024 -0.0595545 3.99984 -0.0104326 3.57569 +EDGE_SE3:QUAT 1261 1330 -4.7143 2.77203 0.0464517 0.00348656 -0.00263905 0.491687 0.870761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 0.000118268 -0.0311974 3.99999 -0.00855297 3.03322 +EDGE_SE3:QUAT 1331 1332 4.36123 -0.27452 0.0209637 0.00175313 -0.00260529 -0.0576804 0.99833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -2.52437e-05 -0.0195279 3.99998 0.000550816 3.98679 +EDGE_SE3:QUAT 256 1331 4.78678 0.311583 0.0193727 -0.00449704 -0.00763304 0.99955 0.0286631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000136097 0.0180104 4.00004 0.031502 0.00361573 +EDGE_SE3:QUAT 257 1331 0.709668 0.367267 0.00186041 -0.0035606 -0.00738892 0.999447 0.0322348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.92665e-05 0.0142637 3.99994 0.0303971 0.00443845 +EDGE_SE3:QUAT 258 1331 -3.69627 0.387133 0.00673651 -0.00210413 -0.00694733 0.999811 0.0180111 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.31344e-05 0.00842084 3.99987 0.0280698 0.00151237 +EDGE_SE3:QUAT 1260 1331 3.99116 6.07434 0.159431 0.00417144 -0.00602072 0.312558 0.94987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 0.000240706 -0.0559195 3.99986 -0.00915454 3.61001 +EDGE_SE3:QUAT 1261 1331 -2.37447 6.40162 0.100807 0.00211536 -0.00311513 0.47977 0.877386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 0.00011513 -0.0271435 4 -0.00664441 3.07947 +EDGE_SE3:QUAT 1332 1333 4.2216 -0.482494 0.00531712 -0.00313351 0.00563749 -0.115571 0.993278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -0.000133256 0.0398948 3.99991 -0.00220671 3.94697 +EDGE_SE3:QUAT 255 1332 4.4804 1.41661 0.00149555 0.00295575 0.00501233 -0.999693 0.0241038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.84989e-05 0.0118342 4.00006 0.0194514 0.00245365 +EDGE_SE3:QUAT 256 1332 0.441037 0.835582 0.00587199 -0.00136768 -0.00645678 0.996218 0.0866404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.0229e-06 0.00549853 3.99984 0.026284 0.0302078 +EDGE_SE3:QUAT 257 1332 -3.62962 0.925318 -0.00184914 -0.000440721 -0.00593553 0.995934 0.0898938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.48835e-05 0.00174957 3.99986 0.0235778 0.0324645 +EDGE_SE3:QUAT 1333 1334 4.27558 -0.733198 0.00420037 -0.00201143 0.000644819 -0.170581 0.985341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.51935e-07 0.000897549 4 4.69943e-05 3.88361 +EDGE_SE3:QUAT 254 1333 3.64695 2.40712 -0.00168924 0.00367603 0.00634889 -0.992219 0.124292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.87985e-05 0.0151386 4.0002 0.0208233 0.0619626 +EDGE_SE3:QUAT 255 1333 0.247466 1.71528 -0.0153478 -0.0080913 -0.00869294 0.995689 0.0919864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000332509 0.0327243 4.00043 0.0399517 0.0345174 +EDGE_SE3:QUAT 256 1333 -3.63193 2.05258 0.0132533 -0.00658826 -0.00917876 0.979445 0.201394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000174251 0.0273113 3.99984 0.0432309 0.162912 +EDGE_SE3:QUAT 1334 1335 4.24243 -0.817869 0.00827914 -0.00121207 -0.000795097 -0.181508 0.983388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.12206e-06 -0.00863109 4 0.000853356 3.86824 +EDGE_SE3:QUAT 252 1334 5.85809 3.77505 0.0257479 0.00332033 0.00763049 -0.93558 0.353016 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -7.12179e-05 0.0182075 4.00042 0.0132323 0.498643 +EDGE_SE3:QUAT 253 1334 2.64491 2.32545 -0.010593 0.000153988 0.00911532 -0.98581 0.167614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000100566 0.00098558 3.99975 0.0337243 0.112672 +EDGE_SE3:QUAT 254 1334 -0.694197 2.07681 -0.0274174 -0.00294278 -0.00922122 0.998854 0.0468735 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.28577e-05 0.0118036 3.99974 0.037783 0.00918106 +EDGE_SE3:QUAT 255 1334 -3.81931 3.23198 -0.0563575 -0.00740001 -0.0118208 0.965289 0.26081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.0883e-05 0.0307903 3.99947 0.0538231 0.273101 +EDGE_SE3:QUAT 1335 1336 4.32407 -0.80188 0.0225925 0.00515975 0.0162572 -0.157425 0.987384 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00444 -0.000718019 0.134974 3.99895 -0.0107472 3.90542 +EDGE_SE3:QUAT 251 1335 5.91667 1.99888 -0.0473802 -0.00636582 0.0108468 -0.967148 0.253904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.63646e-05 -0.0263871 3.99954 0.0486487 0.258675 +EDGE_SE3:QUAT 252 1335 2.1473 1.57078 0.00151426 0.000688307 0.00878918 -0.984014 0.177872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000104913 0.00327726 3.99982 0.0314584 0.126814 +EDGE_SE3:QUAT 253 1335 -1.63113 1.66121 0.00297096 0.00237558 -0.00999601 0.999847 0.0141902 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000104081 -0.00950689 3.99971 0.0396937 0.00122205 +EDGE_SE3:QUAT 254 1335 -4.82556 3.25811 -0.0185533 -0.000684714 -0.0105993 0.973805 0.227137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.00014916 0.00194754 3.99966 0.0382076 0.206753 +EDGE_SE3:QUAT 1336 1337 3.96824 -0.489335 0.00478694 0.00951063 -0.00203649 -0.0839891 0.996419 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -1.81787e-05 -0.00657777 4 0.00013987 3.97179 +EDGE_SE3:QUAT 250 1336 5.98872 0.474584 0.0526684 0.00719705 0.0145115 -0.994556 0.102939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000387766 0.029373 4.00054 0.050667 0.0432539 +EDGE_SE3:QUAT 251 1336 1.76155 0.582698 0.0214766 0.00881306 0.00869597 -0.995046 0.098638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 0.000136099 0.0358285 4.00128 0.0270663 0.0394278 +EDGE_SE3:QUAT 252 1336 -2.17515 0.823321 0.00946987 0.0160846 0.00695221 -0.999638 0.0204093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99893 0.000327042 0.0643734 4.00405 0.0251898 0.00286133 +EDGE_SE3:QUAT 253 1336 -5.8875 2.59228 0.0584931 -0.0122689 -0.0043877 0.985128 0.171329 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000680715 0.0510197 4.00172 0.0326224 0.118351 +EDGE_SE3:QUAT 1337 1338 4.26833 -0.192812 -0.0150981 0.00255096 -0.00357877 -0.0156425 0.999868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -4.0373e-05 -0.0281418 3.99995 0.000219621 3.99922 +EDGE_SE3:QUAT 249 1337 6.12934 0.014093 0.069811 0.0070322 0.00889762 -0.999831 0.0144579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000241582 0.0281402 4.00052 0.0347672 0.00133633 +EDGE_SE3:QUAT 250 1337 2.00133 0.146763 0.00389295 0.00495207 0.00532758 -0.999794 0.0189411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 9.81104e-05 0.0198197 4.0003 0.0205437 0.00163885 +EDGE_SE3:QUAT 251 1337 -2.20572 0.299696 -0.0388122 0.00706929 -0.000174719 -0.999866 0.0147634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -2.26276e-05 0.0282857 4.0008 -0.00153374 0.0010725 +EDGE_SE3:QUAT 252 1337 -6.15151 1.1562 -0.107759 -0.0137712 0.00123947 0.997844 0.064156 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99925 0.00022532 0.0554212 4.00304 0.00213626 0.0172363 +EDGE_SE3:QUAT 1338 1339 4.44659 -0.115661 -0.00711488 0.000836464 0.00585783 -0.00131215 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 1.85349e-05 0.0468812 3.99986 -3.00823e-05 4.00054 +EDGE_SE3:QUAT 248 1338 6.18449 -0.0465093 -0.0174813 0.00337218 -0.00676359 0.999954 0.00588413 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -9.17358e-05 -0.0134903 4.00001 0.0268944 0.00036482 +EDGE_SE3:QUAT 249 1338 1.87093 0.070329 -0.00606415 -0.00319742 -0.00649615 0.999973 0.00125556 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.29704e-05 0.0127904 3.99999 0.0260175 0.00021643 +EDGE_SE3:QUAT 250 1338 -2.24402 0.182685 -0.0518709 0.00137273 0.00285572 -0.99999 0.00314525 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.57412e-05 0.00549106 4 0.0113881 7.9531e-05 +EDGE_SE3:QUAT 251 1338 -6.46304 0.354169 -0.106321 -0.00372852 0.00311477 0.999987 0.00128292 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -4.61323e-05 0.0149142 4.00018 -0.0124216 0.000100764 +EDGE_SE3:QUAT 1339 1340 4.34964 -0.0920062 0.0370007 0.000578995 -0.00513687 0.000539848 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -1.15607e-05 -0.0411024 3.99989 -1.07312e-05 4.00042 +EDGE_SE3:QUAT 247 1339 6.11379 -0.00394214 0.0413665 -0.00824555 -0.00666025 0.999891 0.0102804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.00023261 0.0329887 4.00088 0.0273215 0.000881426 +EDGE_SE3:QUAT 248 1339 1.74855 0.11896 0.0112563 -0.00256408 -0.00621868 0.999952 0.00711039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.26522e-05 0.0102576 3.99995 0.0250178 0.000385017 +EDGE_SE3:QUAT 249 1339 -2.54021 0.189148 -0.0303737 -0.00925419 -0.00553826 0.999938 0.00258977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.000209907 0.0370173 4.00124 0.0223546 0.000494301 +EDGE_SE3:QUAT 250 1339 -6.6445 0.260027 -0.0600082 0.00731169 0.00182062 -0.99997 0.00168451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 5.11672e-05 0.0292462 4.00084 0.00718598 0.000238103 +EDGE_SE3:QUAT 1340 1341 4.46968 -0.0848371 0.0467123 -0.000583994 -0.00243696 0.00250807 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 6.04321e-06 -0.0194783 3.99998 -2.45036e-05 4.00007 +EDGE_SE3:QUAT 246 1340 6.18912 0.0792665 0.0278917 -0.0078002 -0.00506112 0.999902 0.0104508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000170879 0.0312063 4.00085 0.0208977 0.000789532 +EDGE_SE3:QUAT 247 1340 1.77447 0.190047 0.00988704 -0.00296638 -0.00617336 0.999933 0.00928294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.2283e-05 0.0118677 3.99998 0.0249091 0.000535032 +EDGE_SE3:QUAT 248 1340 -2.5599 0.277629 0.0282132 0.00263997 -0.00563244 0.99996 0.00637119 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.99927e-05 -0.010561 3.99999 0.0223935 0.000315624 +EDGE_SE3:QUAT 249 1340 -6.86408 0.322669 -0.073459 -0.00406084 -0.00517071 0.999976 0.0020203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.43663e-05 0.016244 4.00015 0.0207498 0.000189926 +EDGE_SE3:QUAT 1341 1342 4.33528 -0.0684279 0.0132651 -0.00321046 -0.00200972 0.00358175 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.5856e-05 -0.0159394 3.99998 -2.87711e-05 4.00001 +EDGE_SE3:QUAT 245 1341 6.18775 0.172651 0.035497 -0.0064379 -0.00308292 0.999934 0.00897085 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 8.75735e-05 0.0257546 4.00062 0.012794 0.000528664 +EDGE_SE3:QUAT 246 1341 1.72773 0.25476 0.00244879 -0.0054616 -0.00588755 0.999939 0.00763889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000131896 0.0218492 4.00033 0.023884 0.000495366 +EDGE_SE3:QUAT 247 1341 -2.70135 0.345582 0.0295662 -0.000501083 -0.00700597 0.999953 0.00664293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.14632e-05 0.00200458 3.99981 0.0280467 0.000374192 +EDGE_SE3:QUAT 248 1341 -7.02866 0.408013 0.0987426 0.00493101 -0.00633909 0.99996 0.00384751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000124028 -0.0197254 4.00023 0.0252066 0.000315318 +EDGE_SE3:QUAT 1342 1343 4.32965 -0.0772407 -0.0081332 0.000423186 0.000839742 0.00419268 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.48603e-06 0.00669648 4 1.40303e-05 3.99994 +EDGE_SE3:QUAT 244 1342 6.20405 0.201238 0.0272753 -0.00268428 -0.00757176 0.99994 0.00741107 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.9109e-05 0.0107389 3.99988 0.0304423 0.000480228 +EDGE_SE3:QUAT 245 1342 1.85283 0.310597 -0.0064946 -0.00462606 -0.00660178 0.999953 0.00535071 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000123013 0.0185061 4.00016 0.0266058 0.0003771 +EDGE_SE3:QUAT 246 1342 -2.59849 0.396903 -0.0370484 -0.0037137 -0.00994105 0.999937 0.0035945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000145988 0.0148572 3.99982 0.0398707 0.000504297 +EDGE_SE3:QUAT 247 1342 -7.01424 0.489363 0.0378319 0.0010942 -0.0107238 0.999937 0.00310823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.96887e-05 -0.00437763 3.99956 0.0428649 0.000502839 +EDGE_SE3:QUAT 1343 1344 4.38422 -0.0698371 -0.00374509 -0.00204264 0.00749776 0.0053824 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00089 -5.41965e-05 0.0601229 3.99977 0.000159248 4.00079 +EDGE_SE3:QUAT 243 1343 6.29256 0.232213 -0.0207528 0.00370829 -0.00493006 0.999964 0.00577953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -7.23164e-05 -0.0148343 4.00013 0.0195484 0.000284161 +EDGE_SE3:QUAT 244 1343 1.8888 0.346387 -0.000531695 -0.00348677 -0.00709564 0.999964 0.0030116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.86214e-05 0.0139482 3.99999 0.0284671 0.00028751 +EDGE_SE3:QUAT 245 1343 -2.46461 0.440193 -0.0515132 -0.00540034 -0.00604116 0.999967 0.00105367 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000130968 0.0216023 4.00032 0.0242135 0.000267663 +EDGE_SE3:QUAT 246 1343 -6.8913 0.494553 -0.0671753 0.00457509 0.00916266 -0.999947 0.000563254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000167796 0.0183025 4 0.0366327 0.000420491 +EDGE_SE3:QUAT 1344 1345 4.32395 -0.0818646 0.0251249 0.00320912 0.00273632 0.00661103 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 3.57464e-05 0.0216348 3.99997 7.18034e-05 3.99994 +EDGE_SE3:QUAT 242 1344 6.26922 0.231146 -0.00415996 -0.00118235 -0.00819299 0.999958 0.00385675 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.67928e-05 0.00472997 3.99975 0.0328064 0.000334176 +EDGE_SE3:QUAT 243 1344 1.91278 0.352804 0.0111512 -0.00376064 -0.00667819 0.99997 0.000656213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000100456 0.0150435 4.00005 0.026734 0.000236969 +EDGE_SE3:QUAT 244 1344 -2.4751 0.438733 -0.0293937 0.0110452 0.00893948 -0.999897 0.00211978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 0.000390688 0.0441837 4.00164 0.0355927 0.000822592 +EDGE_SE3:QUAT 245 1344 -6.80389 0.518953 -0.0924476 0.0129188 0.00760636 -0.999878 0.00437364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 0.000378316 0.0516766 4.00246 0.0299987 0.000969031 +EDGE_SE3:QUAT 1345 1346 4.23329 -0.06705 0.0288213 -0.000495661 0.000803168 0.00684034 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.49877e-06 0.00646559 4 2.21517e-05 3.99982 +EDGE_SE3:QUAT 241 1345 6.21128 0.260833 0.013367 0.00444993 0.00534301 -0.99997 0.00352004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.42376e-05 0.0178006 4.00021 0.0212481 0.000241643 +EDGE_SE3:QUAT 242 1345 1.92721 0.342625 0.0101335 0.00394748 0.00507867 -0.999975 0.00284634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.97177e-05 0.0157906 4.00015 0.0202259 0.000197009 +EDGE_SE3:QUAT 243 1345 -2.40423 0.441004 0.0109011 0.00645017 0.00342892 -0.999954 0.00615306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 8.28991e-05 0.025802 4.00063 0.0133999 0.00036277 +EDGE_SE3:QUAT 244 1345 -6.78236 0.499722 -0.0982392 0.0138052 0.00595758 -0.999847 0.00893108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99923 0.000291086 0.0552246 4.00294 0.0228628 0.00121225 +EDGE_SE3:QUAT 1346 1347 4.06441 -0.0676831 0.0146504 0.000663842 -0.00587806 0.00438376 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 -1.1991e-05 -0.0470637 3.99986 -0.000102669 4.00048 +EDGE_SE3:QUAT 240 1346 6.29487 0.23009 0.0659573 0.0098682 0.00606027 -0.999845 0.013229 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000211827 0.039483 4.00145 0.0231984 0.00122436 +EDGE_SE3:QUAT 241 1346 1.98732 0.303653 0.00772511 0.00527893 0.00569828 -0.999919 0.010126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000116024 0.0211197 4.00033 0.0223628 0.000646686 +EDGE_SE3:QUAT 242 1346 -2.28492 0.384597 0.0112263 0.00478173 0.00564478 -0.999927 0.00957799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000105023 0.0191302 4.00025 0.0222101 0.000581774 +EDGE_SE3:QUAT 243 1346 -6.6065 0.450649 -0.0190183 0.00750923 0.0041024 -0.999883 0.0126408 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 0.000107599 0.0300439 4.00085 0.0156485 0.000926081 +EDGE_SE3:QUAT 1347 1348 4.39162 -0.12672 0.0174775 5.93783e-05 -0.000178554 -0.0148064 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.31677e-08 -0.00141741 4 1.04663e-05 3.99912 +EDGE_SE3:QUAT 239 1347 6.48874 0.167385 0.0231361 0.00355792 0.00651182 -0.999657 0.0250969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.26259e-05 0.0142467 4.00006 0.0252938 0.00273023 +EDGE_SE3:QUAT 240 1347 2.23778 0.179651 0.00798818 0.00402312 0.00522094 -0.999822 0.0176912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.05973e-05 0.0161007 4.00017 0.0202998 0.00141979 +EDGE_SE3:QUAT 241 1347 -2.06697 0.285868 -0.0217765 -0.000550067 0.00527888 -0.99988 0.0145431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.4416e-06 -0.00220091 3.99989 0.0211681 0.000959268 +EDGE_SE3:QUAT 242 1347 -6.32334 0.368267 -0.0204206 -0.00089492 0.00524224 -0.99989 0.0138314 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.59349e-05 -0.00358073 3.9999 0.0210577 0.000879314 +EDGE_SE3:QUAT 1348 1349 4.16708 -0.235277 0.0126594 -0.00501954 -0.00121926 -0.0472982 0.998867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 3.13632e-05 -0.0125658 3.99999 0.000319106 3.99109 +EDGE_SE3:QUAT 238 1348 6.31859 0.175233 0.0117135 0.0037285 0.00361245 -0.999547 0.029655 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 4.63339e-05 0.0149345 4.00019 0.0135353 0.00361933 +EDGE_SE3:QUAT 239 1348 2.11202 0.0616301 0.00435017 0.00338548 0.00678936 -0.999918 0.0103442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.27588e-05 0.013545 4.00001 0.0268712 0.000654411 +EDGE_SE3:QUAT 240 1348 -2.15698 0.14548 -0.0217945 0.00368792 0.00564424 -0.999974 0.00266213 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.30728e-05 0.0147524 4.00009 0.0224994 0.000209307 +EDGE_SE3:QUAT 241 1348 -6.42837 0.277884 -0.00235945 -0.000619681 0.00531236 -0.999986 2.30351e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.31622e-05 -0.00247883 3.99989 0.0212493 0.000114424 +EDGE_SE3:QUAT 1349 1350 4.14572 -0.370734 0.0234942 -0.00362164 0.0109809 -0.0888496 0.995978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00167 -0.000383907 0.0829965 3.9996 -0.00362843 3.97014 +EDGE_SE3:QUAT 237 1349 6.09893 0.679851 -0.0544556 -0.00419966 0.00476145 -0.99877 0.0491659 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -8.88112e-05 -0.0168555 4.00014 0.0205801 0.00984642 +EDGE_SE3:QUAT 238 1349 2.15512 0.160479 -0.000677492 -0.00233818 -0.00862802 0.999811 0.0172758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 7.2294e-05 0.00935753 3.99977 0.034809 0.00151873 +EDGE_SE3:QUAT 239 1349 -2.04952 0.226176 -0.00480799 -0.00201093 -0.0119779 0.999254 0.0366515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.59907e-05 0.00805646 3.99945 0.0483365 0.00597453 +EDGE_SE3:QUAT 240 1349 -6.29524 0.394403 -0.0330475 -0.00232553 -0.0108103 0.998967 0.0440692 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.22798e-05 0.00932302 3.99957 0.0438479 0.00827177 +EDGE_SE3:QUAT 1350 1351 4.13957 -0.617798 -0.00283299 -0.000390843 0.00448003 -0.141709 0.989898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -7.04111e-05 0.0341125 3.99994 -0.00237611 3.91996 +EDGE_SE3:QUAT 236 1350 5.61419 1.74914 0.00371303 0.000753406 0.00632836 -0.993901 0.110094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.73089e-05 0.00313578 3.99989 0.023894 0.0486303 +EDGE_SE3:QUAT 237 1350 1.94258 0.641763 0.0112925 -0.00621359 -0.00817765 0.999149 0.0399491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000213821 0.0249122 4.00025 0.034568 0.00683824 +EDGE_SE3:QUAT 238 1350 -1.98383 0.677283 0.0180585 -0.0125721 -0.0120751 0.994167 0.106433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000776682 0.0510364 4.00115 0.0575546 0.0468049 +EDGE_SE3:QUAT 239 1350 -6.15172 0.895701 0.0244935 -0.011771 -0.0152415 0.991911 0.125464 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.00072846 0.0479639 4.00025 0.070232 0.0647964 +EDGE_SE3:QUAT 1351 1352 4.03901 -0.719261 0.0197285 0.00541533 -0.00559518 -0.158928 0.98726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -0.000154303 -0.0329219 3.99996 0.0023 3.89923 +EDGE_SE3:QUAT 235 1351 5.00205 2.63298 0.0559131 0.00910341 0.012808 -0.984424 0.175105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99939 0.000114935 0.0385957 4.00163 0.0350063 0.123357 +EDGE_SE3:QUAT 236 1351 1.43908 1.41925 0.00566416 -0.00406246 -0.00689625 0.999446 0.0323027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000110742 0.0162745 4.00003 0.0285634 0.0044443 +EDGE_SE3:QUAT 237 1351 -2.108 1.5651 -0.0169878 -0.0093518 -0.00867316 0.983391 0.181049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000424269 0.0387976 4.00038 0.0449941 0.132019 +EDGE_SE3:QUAT 238 1351 -5.86547 2.12521 -0.0543371 -0.015037 -0.0132753 0.968973 0.24635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.00100633 0.0638191 4.0005 0.0730853 0.245205 +EDGE_SE3:QUAT 1352 1353 4.09999 -0.737473 0.0106132 0.000779237 6.11661e-05 -0.159717 0.987163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.88889e-07 0.00193881 4 -0.000194064 3.89796 +EDGE_SE3:QUAT 234 1352 4.26572 2.8287 0.0117739 0.00354389 0.00809255 -0.975879 0.218132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 6.17935e-05 0.0158223 4.00028 0.0226972 0.190532 +EDGE_SE3:QUAT 235 1352 0.978881 1.91835 -0.00402829 0.00240949 0.00806595 -0.999831 0.0163454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 8.36254e-05 0.00964303 3.99985 0.0319274 0.00134686 +EDGE_SE3:QUAT 236 1352 -2.52241 2.40093 0.00575764 0.00282547 -0.002244 0.981664 0.190587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.65098e-05 -0.0120249 4.00015 0.00401999 0.145336 +EDGE_SE3:QUAT 237 1352 -5.62124 3.67837 -0.0459362 -0.00137615 -0.00570558 0.942041 0.335446 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.18235e-05 0.00462955 3.99989 0.0199385 0.450217 +EDGE_SE3:QUAT 1353 1354 4.29491 -0.706786 -0.0121775 0.00472754 0.00288016 -0.127733 0.991793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 3.69866e-05 0.029648 3.99994 -0.0020344 3.93496 +EDGE_SE3:QUAT 233 1353 3.62934 2.39724 -0.0120124 -0.00234208 0.00647696 -0.965294 0.261075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.23463e-05 -0.00935412 3.99982 0.0261575 0.272847 +EDGE_SE3:QUAT 234 1353 0.248359 1.75242 -0.0110527 0.00254726 0.00788901 -0.998182 0.059697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.5829e-05 0.0102577 3.99992 0.0300638 0.0145082 +EDGE_SE3:QUAT 235 1353 -3.12054 2.52544 0.000999497 -0.00128843 -0.0074663 0.989647 0.14332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.64722e-05 0.00513415 3.99977 0.0297886 0.0823961 +EDGE_SE3:QUAT 1354 1355 4.37966 -0.453383 0.0117579 0.00284037 0.00137362 -0.0629488 0.998012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.57818e-05 0.0130636 3.99999 -0.00043283 3.98419 +EDGE_SE3:QUAT 232 1354 3.44262 1.32582 0.00103746 0.00132751 0.00266217 -0.940936 0.338572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.04527e-05 0.00696845 4.00006 0.00453919 0.458546 +EDGE_SE3:QUAT 233 1354 -0.42343 0.859541 -0.0127229 0.000739798 0.00239733 -0.990746 0.135708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.04605e-06 0.00308776 4 0.00836232 0.0736873 +EDGE_SE3:QUAT 234 1354 -4.09073 1.93189 -0.04633 -0.00444415 -0.00381996 0.997643 0.0683646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.71806e-05 0.0178915 4.0002 0.0175223 0.0188523 +EDGE_SE3:QUAT 1355 1356 4.0354 -0.111361 0.0142879 -0.00114212 -0.00285723 -0.0026517 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 1.25613e-05 -0.0228946 3.99997 3.0149e-05 4.0001 +EDGE_SE3:QUAT 231 1355 4.56407 -0.28997 0.0242292 0.00455925 -0.0023696 -0.877063 0.480348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -6.45453e-05 0.0212764 4 -0.0179548 0.923156 +EDGE_SE3:QUAT 232 1355 -0.221816 -1.10513 -0.00803078 0.00328463 0.000603887 -0.960305 0.278934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -6.28013e-05 0.0146853 4.00016 -0.00480096 0.311279 +EDGE_SE3:QUAT 233 1355 -4.75981 0.107839 -0.0128069 0.00243905 -0.000151836 -0.99734 0.0728507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.16437e-05 0.00983307 4.00009 -0.00201333 0.0212542 +EDGE_SE3:QUAT 1356 1357 4.04303 -0.0489484 0.0203255 -0.00399731 0.000417542 0.00603008 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -7.41755e-06 0.00362932 4 1.12139e-05 3.99986 +EDGE_SE3:QUAT 231 1356 2.30847 -3.60335 0.0130717 0.00148679 -0.00253789 -0.878363 0.477985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.38491e-05 0.0053935 3.99997 -0.00922867 0.913913 +EDGE_SE3:QUAT 232 1356 -3.68365 -3.15876 -0.0144104 0.00030478 0.000849257 -0.961005 0.27653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.97747e-07 0.00149442 4 0.0021426 0.305878 +EDGE_SE3:QUAT 1278 1356 2.47185 4.76915 0.0951431 0.0107885 0.00187784 -0.416903 0.908885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00038 -2.21721e-05 0.0590088 3.99975 -0.015673 3.30562 +EDGE_SE3:QUAT 1279 1356 -3.67942 4.58665 0.113325 0.0112429 0.00505427 -0.245031 0.969437 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00066 7.07987e-05 0.0685943 3.99967 -0.00958353 3.761 +EDGE_SE3:QUAT 1357 1358 4.37138 -0.0470951 0.0170058 -0.00254519 0.00623002 0.00679773 0.999954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0006 -5.74328e-05 0.0500507 3.99984 0.00016803 4.00044 +EDGE_SE3:QUAT 231 1357 0.0837362 -6.94575 0.0305683 -0.000208029 0.0014075 -0.87541 0.48338 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.32013e-06 0.000202906 4 0.00324188 0.934629 +EDGE_SE3:QUAT 1278 1357 5.07653 1.68656 0.0613116 0.00729607 0.00393601 -0.411256 0.911482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 -0.000199688 0.0558034 3.99986 -0.0132822 3.32425 +EDGE_SE3:QUAT 1279 1357 -0.142674 2.62495 0.0618236 0.00726503 0.00647964 -0.239559 0.970833 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00093 -0.000115345 0.0675405 3.99973 -0.00873017 3.77158 +EDGE_SE3:QUAT 1280 1357 -4.89869 2.01432 -0.084662 0.00372104 -0.00737941 -0.0992122 0.995032 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00067 -0.000209619 -0.0537714 3.99984 0.00258521 3.96135 +EDGE_SE3:QUAT 1358 1359 4.01376 -0.0668597 0.00742652 0.000189437 0.00236666 0.00733867 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.77626e-06 0.0189155 3.99998 6.94144e-05 3.99987 +EDGE_SE3:QUAT 1279 1358 3.72111 0.532509 0.0105946 0.00628394 0.0131395 -0.232433 0.972503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00307 -0.000753148 0.113691 3.99933 -0.0135449 3.78713 +EDGE_SE3:QUAT 1280 1358 -0.616153 1.10194 -0.00471426 0.00187137 -0.00104435 -0.0921825 0.99574 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.65491e-06 -0.00619015 4 0.000251895 3.96602 +EDGE_SE3:QUAT 1281 1358 -5.11215 0.807426 -0.0121148 -0.0024861 -0.0011682 -0.0151139 0.999882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.18264e-05 -0.00979317 3.99999 7.50474e-05 3.99911 +EDGE_SE3:QUAT 1359 1360 4.4019 -0.0410306 0.0257839 -0.00028656 -0.000822508 0.00780868 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.06352e-06 -0.00655262 4 -2.55527e-05 3.99977 +EDGE_SE3:QUAT 1279 1359 7.2689 -1.35051 -0.0930462 0.00725987 0.0153048 -0.225383 0.974123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00416 -0.000975604 0.132326 3.99907 -0.01528 3.80118 +EDGE_SE3:QUAT 1280 1359 3.34222 0.294629 0.00481095 0.00202424 0.00131939 -0.0848445 0.996391 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 8.65512e-06 0.0124924 3.99999 -0.00055738 3.97124 +EDGE_SE3:QUAT 1281 1359 -1.10269 0.613121 0.00325674 -0.00240497 0.00123803 -0.0077081 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.18254e-05 0.0096809 3.99999 -3.71096e-05 3.99979 +EDGE_SE3:QUAT 1282 1359 -5.22893 0.625805 -0.00909385 -0.000627837 0.00149541 0.0072703 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -3.38519e-06 0.0120172 3.99999 4.37166e-05 3.99982 +EDGE_SE3:QUAT 1360 1361 4.33126 -0.0925165 0.0263792 -0.00317568 -0.000372866 -0.0123482 0.999919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.67914e-06 -0.00345272 4 2.22711e-05 3.99939 +EDGE_SE3:QUAT 941 1360 5.26971 -3.29198 0.0412408 -0.00691039 -0.00265006 0.978817 0.204605 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000233649 0.0291424 4.00049 0.0203493 0.167779 +EDGE_SE3:QUAT 942 1360 -0.823941 -4.04345 0.0714088 -0.00355566 0.00435393 0.910746 0.412928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000148244 0.0198229 4.00034 -0.000708778 0.682158 +EDGE_SE3:QUAT 943 1360 -6.57001 -2.53607 0.0672046 -0.000953673 0.00161238 0.811846 0.583869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.51897e-05 0.00777593 4.00003 0.00126998 1.36363 +EDGE_SE3:QUAT 1222 1360 -2.15464 6.70911 0.142781 0.00676811 0.00729687 -0.310346 0.950572 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00118 -0.000339642 0.0737567 3.99973 -0.0122705 3.6161 +EDGE_SE3:QUAT 1281 1360 3.29307 0.487979 0.0172975 -0.00250373 0.000328337 0.000121688 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.29401e-06 0.00263033 4 1.53621e-07 4 +EDGE_SE3:QUAT 1282 1360 -0.841109 0.638219 0.00339233 -0.000886458 0.000832841 0.0151439 0.999885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -2.78542e-06 0.00682152 4 5.20382e-05 3.99909 +EDGE_SE3:QUAT 1283 1360 -4.82738 0.691013 0.00193826 0.000423164 0.00220115 0.019798 0.999801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 5.97492e-06 0.0174986 3.99998 0.000172911 3.99851 +EDGE_SE3:QUAT 1361 1362 3.97898 -0.26987 0.0253594 0.00136659 -0.00321303 -0.063237 0.997992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -3.10725e-05 -0.0245166 3.99996 0.000763014 3.98415 +EDGE_SE3:QUAT 940 1361 5.74817 -0.296555 0.0446095 -0.00884832 -0.00468269 0.999264 0.0370376 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000225246 0.0354648 4.00109 0.0212934 0.00591544 +EDGE_SE3:QUAT 941 1361 1.32576 -1.45456 0.012639 -0.00735911 -0.00587956 0.976135 0.216959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000259355 0.0309641 4.00025 0.0329732 0.188813 +EDGE_SE3:QUAT 942 1361 -3.61489 -0.723194 0.0553879 -0.0045757 0.00140794 0.905425 0.42448 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000180176 0.0234063 4.00027 0.00947853 0.72091 +EDGE_SE3:QUAT 1221 1361 6.56828 2.58974 0.0991681 0.00619239 0.0054983 -0.486673 0.873545 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00074 -0.000461919 0.0597909 3.99997 -0.0158872 3.05349 +EDGE_SE3:QUAT 1222 1361 1.2988 4.05835 0.0861086 0.00366367 0.00804405 -0.322118 0.946658 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00109 -0.000446497 0.0678006 3.99983 -0.011098 3.58611 +EDGE_SE3:QUAT 1223 1361 -4.17262 3.67486 -0.00631894 -0.00242955 0.00270004 -0.156834 0.987618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.57854e-05 0.0163108 3.99999 -0.00113869 3.90168 +EDGE_SE3:QUAT 1282 1361 3.4878 0.666798 0.0214312 -0.00407631 0.000489031 0.00279549 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -8.32808e-06 0.00404885 4 5.69823e-06 3.99997 +EDGE_SE3:QUAT 1283 1361 -0.496398 0.772958 0.00981186 -0.00291685 0.00195133 0.00726817 0.999967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.2579e-05 0.0158638 3.99998 5.76858e-05 3.99985 +EDGE_SE3:QUAT 1284 1361 -4.53692 0.867131 0.00295381 -0.00438253 0.00370896 0.00973259 0.999936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -6.32125e-05 0.03018 3.99994 0.000146223 3.99985 +EDGE_SE3:QUAT 1362 1363 4.18666 -0.565547 -0.0152752 -8.18212e-05 0.00571536 -0.143486 0.989636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 -0.000109545 0.0441838 3.99989 -0.00313335 3.91813 +EDGE_SE3:QUAT 939 1362 5.91424 1.44964 -0.0164037 -0.00375697 0.00404293 -0.997292 0.0733295 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -7.08035e-05 -0.0151363 4.00011 0.0181478 0.0216491 +EDGE_SE3:QUAT 940 1362 1.81979 0.276119 0.0016835 -0.00537972 -0.00407327 0.994949 0.100153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000129346 0.0218084 4.00028 0.0201556 0.0403449 +EDGE_SE3:QUAT 941 1362 -2.1717 0.481847 -0.00420433 -0.00367606 -0.00565976 0.9605 0.278198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.8579e-05 0.0153357 3.99987 0.0259272 0.309817 +EDGE_SE3:QUAT 942 1362 -5.93468 2.48552 0.0495499 -0.00125662 0.00104911 0.876858 0.480747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.04926e-05 0.00737736 4.00003 0.0017372 0.924486 +EDGE_SE3:QUAT 1222 1362 4.27414 1.41546 0.039395 0.00329449 0.00503984 -0.381535 0.924335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -0.000226241 0.0454687 3.99994 -0.0090002 3.41824 +EDGE_SE3:QUAT 1223 1362 -0.486301 2.18489 0.000298121 -0.00175693 -0.0010323 -0.218985 0.975726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.10451e-06 -0.0121409 3.99999 0.00147512 3.80822 +EDGE_SE3:QUAT 1224 1362 -5.2717 1.66699 0.030499 -0.000230161 0.000126588 -0.109446 0.993993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.1751e-08 0.000694696 4 -3.21674e-05 3.95209 +EDGE_SE3:QUAT 1282 1362 7.45652 0.426663 0.0462751 -0.00279508 -0.00308226 -0.0604376 0.998163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 2.24856e-05 -0.026546 3.99995 0.000820612 3.98557 +EDGE_SE3:QUAT 1283 1362 3.47581 0.557681 0.016765 -0.0016296 -0.00146481 -0.0558747 0.998435 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 7.38256e-06 -0.0127541 3.99999 0.000365891 3.98755 +EDGE_SE3:QUAT 1284 1362 -0.565125 0.657177 0.00382065 -0.00307234 0.000310795 -0.0534079 0.998568 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.12566e-07 0.000510412 4 3.99121e-06 3.98859 +EDGE_SE3:QUAT 1285 1362 -4.61871 0.747094 0.0157926 -0.00259139 -0.00124755 -0.0515899 0.998664 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.32033e-05 -0.011542 3.99999 0.000311058 3.98939 +EDGE_SE3:QUAT 1363 1364 4.1841 -0.893636 0.0184806 -0.00283111 -0.000431723 -0.208702 0.977975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.15778e-05 -0.010115 3.99999 0.00129372 3.8258 +EDGE_SE3:QUAT 938 1363 5.18597 2.48651 0.0178078 0.00289553 0.00827038 -0.994868 0.100805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000113128 0.011826 3.99999 0.0299342 0.040909 +EDGE_SE3:QUAT 939 1363 1.7151 1.39951 -0.00326795 -0.0015391 -0.00391139 0.997502 0.0705171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.77079e-05 0.0061913 3.99996 0.0163153 0.0199671 +EDGE_SE3:QUAT 940 1363 -2.13849 1.65661 -0.0463162 -0.0105604 -0.0041434 0.970221 0.241954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000575554 0.0453237 4.00099 0.0334576 0.234991 +EDGE_SE3:QUAT 941 1363 -5.32565 3.15138 -0.0330087 -0.00847861 -0.0050057 0.910532 0.413322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 0.000262521 0.0386117 4.00005 0.035251 0.684088 +EDGE_SE3:QUAT 1222 1363 6.81777 -1.91203 -0.0318759 0.00453399 0.0108601 -0.510022 0.860081 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00139 -0.00122405 0.0782534 4.00023 -0.0187683 2.96099 +EDGE_SE3:QUAT 1223 1363 3.04806 -0.11228 -0.00292955 -0.000158687 0.00433914 -0.356579 0.934255 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -0.000122855 0.0276871 3.99999 -0.00446541 3.49159 +EDGE_SE3:QUAT 1224 1363 -1.33829 0.198831 0.0110466 0.000312799 0.00583092 -0.250905 0.967994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -0.000181024 0.043219 3.99992 -0.00526991 3.74865 +EDGE_SE3:QUAT 1225 1363 -5.46144 0.104575 -0.00150266 0.00025259 0.00576283 -0.218641 0.975788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -0.000157564 0.0434826 3.99991 -0.0046543 3.80926 +EDGE_SE3:QUAT 1284 1363 3.54242 -0.348866 -0.0106654 -0.00296115 0.00567219 -0.19604 0.980575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -0.000156904 0.0360006 3.99995 -0.00321596 3.84659 +EDGE_SE3:QUAT 1285 1363 -0.549964 -0.259718 0.00967945 -0.00212927 0.00412295 -0.194202 0.98095 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -8.26762e-05 0.0262986 3.99997 -0.002332 3.84931 +EDGE_SE3:QUAT 1286 1363 -4.52465 -0.187412 -0.0010986 -0.000707793 0.0047564 -0.192729 0.98124 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -0.000102723 0.0343566 3.99994 -0.00318926 3.85172 +EDGE_SE3:QUAT 1364 1365 3.89348 -0.802366 0.00531605 0.00356307 0.00373244 -0.190239 0.981724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -1.96922e-05 0.0361934 3.99992 -0.00364663 3.85556 +EDGE_SE3:QUAT 937 1364 3.46316 3.67907 0.00583593 -0.000706907 0.0112284 -0.982842 0.184104 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000140582 -0.00240584 3.99957 0.042157 0.13604 +EDGE_SE3:QUAT 938 1364 0.908642 2.52436 0.0136467 -0.000628149 -0.0114979 0.993982 0.108935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.46104e-05 0.00243721 3.99949 0.0451709 0.047985 +EDGE_SE3:QUAT 939 1364 -2.30473 2.88742 0.0117979 -0.000680806 -0.00688393 0.960878 0.276887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -6.97633e-05 0.00184856 3.99987 0.0237942 0.306823 +EDGE_SE3:QUAT 940 1364 -5.40914 4.41903 -0.0967583 -0.0102205 -0.00918402 0.898301 0.439165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 0.000114019 0.0446797 3.99959 0.049251 0.772716 +EDGE_SE3:QUAT 1223 1364 5.57801 -3.57402 -0.0177777 -0.0039145 0.00496106 -0.543831 0.839171 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 7.6886e-06 0.00294545 4.00001 0.00336447 2.81695 +EDGE_SE3:QUAT 1224 1364 1.89782 -2.62235 -0.0210127 -0.00370056 0.00636816 -0.447279 0.894364 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000129626 0.0192338 4.00005 -0.00153849 3.19982 +EDGE_SE3:QUAT 1225 1364 -2.04138 -2.49138 -0.0328018 -0.00360573 0.00616541 -0.417603 0.908601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -0.000137804 0.0210303 4.00004 -0.0021371 3.30251 +EDGE_SE3:QUAT 1226 1364 -6.34717 -2.53423 -0.0644188 -0.00263776 0.00624462 -0.405198 0.914204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -0.000184946 0.0267503 4.00004 -0.00363224 3.34341 +EDGE_SE3:QUAT 1285 1364 2.99862 -2.67871 0.000123299 -0.00561321 0.00384406 -0.394799 0.918742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 2.79154e-05 1.95351e-05 4 0.00225289 3.37651 +EDGE_SE3:QUAT 1286 1364 -0.996629 -2.59484 -0.0224659 -0.0042974 0.00499739 -0.393069 0.919485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -5.79543e-05 0.0128975 4.00002 -0.000545508 3.382 +EDGE_SE3:QUAT 1287 1364 -4.97101 -2.50818 -0.0366005 -0.00423872 0.00581341 -0.391528 0.920138 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000106319 0.0183524 4.00003 -0.00153087 3.38688 +EDGE_SE3:QUAT 1365 1366 3.97214 -0.67891 0.0192919 0.00681586 0.0154843 -0.14285 0.9896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00415 -0.000455562 0.13175 3.99896 -0.00957907 3.92271 +EDGE_SE3:QUAT 936 1365 2.33186 3.03165 0.0362277 0.0034021 0.0101029 -0.977709 0.209696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000129434 0.0152215 4.00021 0.0305856 0.176201 +EDGE_SE3:QUAT 937 1365 -0.443059 3.02964 0.0271276 -0.00161378 -0.00772175 0.999952 0.00583898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.73934e-05 0.00645598 3.9998 0.0309592 0.000386433 +EDGE_SE3:QUAT 938 1365 -2.71654 4.11955 0.0445617 -0.00196147 -0.00727589 0.955146 0.29604 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.06642e-05 0.00729723 3.9998 0.0271638 0.350778 +EDGE_SE3:QUAT 1224 1365 3.59023 -6.2011 -0.0352971 0.000379906 0.00728329 -0.60925 0.792945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -0.000341205 0.0311424 4.00019 -0.00547011 2.51543 +EDGE_SE3:QUAT 1225 1365 -0.109376 -5.94161 -0.049267 0.000432081 0.00739784 -0.582817 0.81257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.0003737 0.0340931 4.00018 -0.00648768 2.64153 +EDGE_SE3:QUAT 1226 1365 -4.32887 -5.93891 -0.0778458 0.00112847 0.00743159 -0.571783 0.82037 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 -0.000436806 0.0388848 4.00019 -0.00830928 2.69258 +EDGE_SE3:QUAT 1286 1365 1.12108 -5.94404 -0.0257119 -0.000340429 0.00599957 -0.560865 0.827885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -0.000212989 0.0254252 4.0001 -0.00428401 2.74184 +EDGE_SE3:QUAT 1287 1365 -2.83909 -5.84929 -0.0472449 -0.00029516 0.00706469 -0.559717 0.828654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -0.000303236 0.0305929 4.00014 -0.00529625 2.74705 +EDGE_SE3:QUAT 1366 1367 4.19865 -0.372599 -0.0591598 0.00163049 0.0140044 -0.05013 0.998643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00316 -0.000146121 0.11267 3.99921 -0.00282686 3.99312 +EDGE_SE3:QUAT 936 1366 -1.55004 2.0403 0.0276764 0.0185539 0.00721125 -0.997464 0.0683272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99853 -3.47143e-05 0.0747368 4.00567 0.0184453 0.0201637 +EDGE_SE3:QUAT 937 1366 -4.38319 3.76612 0.0435333 -0.0157226 -0.00111158 0.988796 0.148439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99922 0.000890921 0.0649076 4.00358 0.0224974 0.0893384 +EDGE_SE3:QUAT 1367 1368 3.97384 -0.101077 0.0101211 0.000440283 0.000930608 -0.00437431 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.55431e-06 0.00746778 4 -1.63408e-05 3.99994 +EDGE_SE3:QUAT 936 1367 -5.74685 1.83382 -0.191034 0.0319609 0.00725849 -0.999312 0.0173716 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99586 0.000516446 0.127839 4.01636 0.0247044 0.0054501 +EDGE_SE3:QUAT 1368 1369 4.02344 -0.0998056 0.0296246 -0.00235443 0.00292875 -0.0026664 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -2.80127e-05 0.0233549 3.99997 -3.15882e-05 4.00011 +EDGE_SE3:QUAT 1369 1370 4.30292 -0.101731 0.0174511 0.00200369 0.000631199 -0.00128892 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.08783e-06 0.00508055 4 -3.26153e-06 4 +EDGE_SE3:QUAT 931 1369 7.14829 1.53188 0.0903239 -0.00466344 -0.0084551 0.999948 0.0031769 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.00015756 0.0186559 4.00006 0.0339409 0.000415366 +EDGE_SE3:QUAT 932 1369 2.95838 1.6297 0.0776823 -0.00639881 -0.00825063 0.999943 0.00241346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000212305 0.0255976 4.00038 0.0331319 0.000461499 +EDGE_SE3:QUAT 933 1369 -1.0684 1.71451 0.0406358 -0.00861002 -0.00911024 0.99992 0.00193774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 0.000316171 0.0344434 4.00085 0.0365874 0.000646169 +EDGE_SE3:QUAT 934 1369 -5.33866 1.80308 0.0136808 -0.00775954 -0.00705563 0.999944 0.00151147 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.00022073 0.0310397 4.00076 0.0283248 0.000450531 +EDGE_SE3:QUAT 1370 1371 4.04771 -0.0879435 0.0212344 -0.000279311 -0.000993681 0.000646811 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.12512e-06 -0.0079473 4 -2.57661e-06 4.00001 +EDGE_SE3:QUAT 930 1370 7.15139 1.54459 0.0668147 -0.0035939 -0.00714737 0.999946 0.00660563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000102032 0.0143776 3.99999 0.0287775 0.000433259 +EDGE_SE3:QUAT 931 1370 2.83474 1.65533 0.0673095 -0.00522539 -0.0065058 0.999954 0.00478722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000137487 0.0209034 4.00026 0.0262251 0.000372836 +EDGE_SE3:QUAT 932 1370 -1.35599 1.75644 0.0448861 -0.00707758 -0.00633301 0.999947 0.00400127 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000182881 0.0283121 4.00063 0.0255641 0.000427788 +EDGE_SE3:QUAT 933 1370 -5.3859 1.83704 -0.00880369 -0.00909093 -0.00782901 0.999921 0.00379478 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000290585 0.0363665 4.00106 0.0316042 0.000637865 +EDGE_SE3:QUAT 1371 1372 4.08302 -0.0870167 0.0220204 -0.000439979 0.0023122 0.000769286 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -3.97203e-06 0.018502 3.99998 7.0611e-06 4.00008 +EDGE_SE3:QUAT 930 1371 3.09784 1.67306 0.0637835 -0.00259526 -0.00736865 0.999953 0.00579227 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.48724e-05 0.0103824 3.99989 0.0295926 0.000380093 +EDGE_SE3:QUAT 931 1371 -1.20233 1.78574 0.0541885 -0.00432615 -0.00702525 0.999957 0.00415091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.00012178 0.0173062 4.0001 0.0282456 0.000343244 +EDGE_SE3:QUAT 932 1371 -5.39698 1.86837 0.0140281 -0.00626907 -0.00783606 0.999943 0.00353209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000198139 0.0250786 4.00037 0.0315262 0.000455581 +EDGE_SE3:QUAT 1372 1373 4.33349 -0.103353 0.0223909 0.0015406 0.000432204 0.00099711 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.6489e-06 0.00343918 4 1.71841e-06 4 +EDGE_SE3:QUAT 929 1372 3.39287 1.71445 0.0718607 -0.00286476 -0.00933274 0.999933 0.00624475 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.00010375 0.0114611 3.99977 0.0374704 0.000539864 +EDGE_SE3:QUAT 930 1372 -0.958182 1.82073 0.064105 -0.00509773 -0.00788002 0.999944 0.0049911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000161287 0.0203934 4.00016 0.0317251 0.000455226 +EDGE_SE3:QUAT 931 1372 -5.24875 1.90163 0.0383459 -0.00685294 -0.00716259 0.999945 0.00350707 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000198922 0.0274138 4.00054 0.0288484 0.000445101 +EDGE_SE3:QUAT 1373 1374 4.17327 -0.0996524 0.0307436 -0.00091559 0.00272038 0.000308826 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -9.91121e-06 0.0217669 3.99997 3.19887e-06 4.00012 +EDGE_SE3:QUAT 928 1373 3.52025 1.76287 0.066719 -0.00543358 -0.00557488 0.999954 0.00566584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000123752 0.0217361 4.00034 0.0225473 0.000373609 +EDGE_SE3:QUAT 929 1373 -0.92892 1.85889 0.0728146 -0.00334229 -0.00774571 0.99995 0.00538548 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000102368 0.0133709 3.99993 0.0311255 0.000402915 +EDGE_SE3:QUAT 930 1373 -5.24329 1.95102 0.0500597 -0.00559325 -0.00621075 0.999956 0.00428646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000140857 0.0223746 4.00034 0.0250374 0.000355355 +EDGE_SE3:QUAT 1374 1375 4.42072 -0.0941162 0.0404787 -0.000920576 0.000967586 -0.000565914 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.57185e-06 0.00773445 4 -2.20861e-06 4.00001 +EDGE_SE3:QUAT 927 1374 3.72641 1.80684 0.0743134 -0.00589359 -0.00666935 0.999954 0.0036219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000158985 0.023576 4.00037 0.0268518 0.000371664 +EDGE_SE3:QUAT 928 1374 -0.678457 1.89701 0.0603562 -0.00793914 -0.00649603 0.999933 0.00545432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000212766 0.0317591 4.00083 0.0263371 0.00054454 +EDGE_SE3:QUAT 929 1374 -5.06924 1.99638 0.0852824 -0.00603578 -0.00865756 0.999932 0.00504896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000210395 0.0241464 4.00027 0.0348774 0.000551812 +EDGE_SE3:QUAT 1375 1376 4.23409 -0.0944502 0.0350317 0.00136332 -0.00101356 0.000396773 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -5.52343e-06 -0.00811502 4 -1.5767e-06 4.00002 +EDGE_SE3:QUAT 926 1375 3.72753 1.85632 0.0702278 0.00462269 0.00694167 -0.999965 0.000313415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000128343 0.0184919 4.00015 0.0277577 0.000278489 +EDGE_SE3:QUAT 927 1375 -0.68322 1.92123 0.0637512 -0.00699312 -0.00737256 0.999939 0.00425456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000209429 0.0279749 4.00055 0.029734 0.000489046 +EDGE_SE3:QUAT 928 1375 -5.07791 2.03772 0.0323104 -0.00921956 -0.0070713 0.999915 0.00589549 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000270583 0.0368815 4.00114 0.0287302 0.000685397 +EDGE_SE3:QUAT 1376 1377 4.00259 -0.0764111 0.0282165 -0.00134697 -0.000277562 0.00161279 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.47498e-06 -0.00219442 4 -1.765e-06 3.99999 +EDGE_SE3:QUAT 925 1376 3.85085 1.85005 0.0661568 0.00397971 0.00476513 -0.99998 0.00137527 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 7.55937e-05 0.0159193 4.00016 0.0190181 0.000161338 +EDGE_SE3:QUAT 926 1376 -0.49228 1.94934 0.0651295 0.00360377 0.00558773 -0.999977 0.00103146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.0492e-05 0.0144157 4.00008 0.0223224 0.000180776 +EDGE_SE3:QUAT 927 1376 -4.88889 2.05262 0.0419072 -0.00599295 -0.00619119 0.999957 0.00355909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000150423 0.0239733 4.00041 0.024939 0.000349818 +EDGE_SE3:QUAT 1377 1378 4.23124 -0.0800016 0.0258573 7.75226e-05 0.00111536 0.00305243 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.36806e-07 0.00891997 4 1.36148e-05 3.99998 +EDGE_SE3:QUAT 924 1377 4.18557 1.83088 0.0589675 0.00311079 0.00585469 -0.999972 0.00347954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.29879e-05 0.012444 4.00002 0.0233323 0.00022324 +EDGE_SE3:QUAT 925 1377 -0.140984 1.9207 0.0708119 0.00375037 0.00690166 -0.999965 0.00300721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000103662 0.0150026 4.00004 0.0275173 0.000281739 +EDGE_SE3:QUAT 926 1377 -4.46768 2.01568 0.0708707 0.00355194 0.00682458 -0.999968 0.00219558 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 9.71162e-05 0.0142088 4.00002 0.0272369 0.000255213 +EDGE_SE3:QUAT 1378 1379 4.03117 -0.0727733 0.0243355 0.00230788 -0.00118877 0.00175687 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.09889e-05 -0.0095587 3.99999 -8.33216e-06 4.00001 +EDGE_SE3:QUAT 923 1378 4.22474 1.7796 0.0596991 0.00289561 0.00617524 -0.999948 0.00752418 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.22439e-05 0.011584 3.99999 0.0245239 0.000410365 +EDGE_SE3:QUAT 924 1378 -0.0552244 1.87019 0.0623085 0.00434298 0.00597436 -0.99995 0.00674215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000102604 0.0173738 4.00017 0.0236626 0.000397269 +EDGE_SE3:QUAT 925 1378 -4.35834 1.97381 0.0706303 0.00512428 0.00646239 -0.999945 0.00646928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000130495 0.0204994 4.00026 0.0255849 0.000436104 +EDGE_SE3:QUAT 1379 1380 4.19313 -0.123412 -0.00211379 -0.00159094 0.00667309 -0.0202739 0.999771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00069 -6.3458e-05 0.0529727 3.99983 -0.000537492 3.99906 +EDGE_SE3:QUAT 922 1379 4.53804 1.70747 0.0445726 -0.003058 0.00881291 -0.999909 0.00971947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000103777 -0.012235 3.99983 0.0354814 0.00073007 +EDGE_SE3:QUAT 923 1379 0.180687 1.79425 0.0641332 0.00177469 0.00393351 -0.99995 0.00899321 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.83204e-05 0.00709979 3.99999 0.0156033 0.000396985 +EDGE_SE3:QUAT 924 1379 -4.04989 1.90649 0.0506104 0.00330138 0.00366159 -0.999954 0.00818824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 4.70441e-05 0.0132071 4.00013 0.0144285 0.000363845 +EDGE_SE3:QUAT 1380 1381 4.02186 -0.314244 0.03126 0.00369166 -0.00271659 -0.0735159 0.997284 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -4.17376e-05 -0.0183116 3.99998 0.000631567 3.97847 +EDGE_SE3:QUAT 921 1380 4.62747 1.66078 0.0755027 -0.00565287 -0.00860252 0.999902 0.00943746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000195944 0.0226167 4.00019 0.0348338 0.000787497 +EDGE_SE3:QUAT 922 1380 0.353487 1.74201 0.0700844 -0.00317678 -0.0101299 0.999888 0.0105243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000122396 0.012711 3.99974 0.0407756 0.000899172 +EDGE_SE3:QUAT 923 1380 -3.9835 1.86261 0.0522135 -0.00825349 -0.00530008 0.999888 0.0113263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000190744 0.0330208 4.00095 0.0219491 0.0009062 +EDGE_SE3:QUAT 1381 1382 4.25532 -0.680451 0.0123061 -0.00102157 -0.00690104 -0.16916 0.985564 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 -0.000166426 -0.0548989 3.99983 0.00463476 3.88629 +EDGE_SE3:QUAT 920 1381 4.89459 1.9808 0.055934 -0.00178357 -0.00613567 0.996613 0.0819845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.13307e-05 0.00717911 3.99986 0.0252929 0.0270598 +EDGE_SE3:QUAT 921 1381 0.62531 2.05988 0.0709965 -0.00230498 -0.00546313 0.996539 0.0829142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.61188e-05 0.00928999 3.99992 0.0229963 0.0276538 +EDGE_SE3:QUAT 922 1381 -3.63349 2.16155 0.0837374 0.000189674 -0.00710831 0.996449 0.083896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.75593e-05 -0.00080052 3.99982 0.0278072 0.0283491 +EDGE_SE3:QUAT 1382 1383 4.17473 -1.03738 0.0160361 0.00680821 -0.00394918 -0.22355 0.974661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -3.73168e-05 -0.0115977 4 0.000525789 3.80012 +EDGE_SE3:QUAT 919 1382 4.83742 3.2452 0.132702 -0.0200082 -0.0151102 0.968541 0.247587 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.00188314 0.0852937 4.00158 0.0886647 0.249134 +EDGE_SE3:QUAT 920 1382 0.819226 3.33581 0.06536 0.00597463 -0.00766338 0.968463 0.248968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 9.14381e-05 -0.0269593 4.00083 0.0148488 0.248201 +EDGE_SE3:QUAT 921 1382 -3.44638 3.40287 0.0717411 0.00512396 -0.00702332 0.968158 0.250187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 5.93678e-05 -0.0232066 4.00062 0.0141836 0.250578 +EDGE_SE3:QUAT 1383 1384 4.0373 -0.831769 -0.0129455 0.0017493 -0.000575698 -0.183739 0.982973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.26605e-07 -0.000604148 4 -6.98649e-05 3.86496 +EDGE_SE3:QUAT 919 1383 1.6696 6.12369 0.0627376 -0.0101139 -0.0133311 0.888798 0.457993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000264534 0.0408034 3.99908 0.0567849 0.840489 +EDGE_SE3:QUAT 920 1383 -2.34331 6.21897 0.161474 0.0132509 -0.000723144 0.888289 0.459094 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 0.00129973 -0.067522 4.00142 -0.0369537 0.844698 +EDGE_SE3:QUAT 1384 1385 4.11875 -0.653373 0.00426646 0.00877145 -0.00485321 -0.11665 0.993123 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000130576 -0.0258655 3.99997 0.00125723 3.94573 +EDGE_SE3:QUAT 1385 1386 4.18345 -0.221305 0.00574187 0.000551589 0.00108779 -0.0242945 0.999704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.74722e-06 0.00885536 4 -0.000108173 3.99766 +EDGE_SE3:QUAT 1386 1387 4.09803 -0.0394673 0.00936116 -0.000195155 0.00260429 0.0151977 0.999881 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 4.42576e-07 0.0208632 3.99997 0.000158587 3.99918 +EDGE_SE3:QUAT 1387 1388 4.07658 -0.0368326 0.0165601 -0.00101348 -3.68372e-06 0.00889598 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.81565e-08 7.87191e-05 4 5.10559e-07 3.99968 +EDGE_SE3:QUAT 1388 1389 4.26152 -0.100293 -0.0222022 -0.000113307 0.00889619 -0.0031717 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00127 -1.0062e-05 0.0711838 3.99968 -0.000113193 4.00123 +EDGE_SE3:QUAT 1389 1390 4.1766 -0.0640516 0.00611047 -0.00450007 0.00485652 0.00354523 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -8.59942e-05 0.0390449 3.9999 6.67738e-05 4.00033 +EDGE_SE3:QUAT 1390 1391 4.22739 -0.0747426 0.0225899 0.00392271 -0.00098008 0.00755472 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -1.61196e-05 -0.00819542 4 -3.13072e-05 3.99979 +EDGE_SE3:QUAT 108 1390 3.63147 -5.96817 0.0345463 -0.0033375 0.00067104 0.916052 0.401044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.70701e-05 0.0165098 4.00013 0.00731832 0.643435 +EDGE_SE3:QUAT 109 1390 -3.29795 -5.96148 0.0504203 -0.00578368 0.000957184 0.804564 0.593837 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 0.000263416 0.0333486 4.00017 0.0168814 1.41097 +EDGE_SE3:QUAT 1391 1392 4.17496 -0.0377541 0.0261426 -0.00274718 -6.90851e-05 0.00263709 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.00152e-07 -0.000465735 4 -5.76121e-07 3.99997 +EDGE_SE3:QUAT 107 1391 6.25229 -1.05281 -0.0207358 -0.0011176 -0.0049158 0.990924 0.13433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.23713e-06 0.00449447 3.9999 0.0199609 0.0722848 +EDGE_SE3:QUAT 108 1391 0.811543 -2.81749 0.0331588 -0.000749795 0.00401057 0.919105 0.393992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.82208e-07 0.00557457 4.00005 -0.00817076 0.620952 +EDGE_SE3:QUAT 109 1391 -4.47896 -1.88991 0.021721 -0.00268291 0.00362713 0.809051 0.587722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 0.000165312 0.0205718 4.00019 0.00462919 1.38181 +EDGE_SE3:QUAT 1392 1393 4.34533 -0.209813 0.0259799 -0.00712717 -0.00249127 -0.0558844 0.998409 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.16029e-05 -0.0246057 3.99996 0.000729742 3.98766 +EDGE_SE3:QUAT 106 1392 6.05863 1.77211 0.0568646 0.00821727 0.00595416 -0.994574 0.103535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 2.61142e-05 0.0334446 4.00115 0.0164536 0.0432295 +EDGE_SE3:QUAT 107 1392 2.23742 0.0934394 0.00481804 -0.00159417 -0.00766446 0.991267 0.13164 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.37463e-05 0.00640047 3.99976 0.0309865 0.0695705 +EDGE_SE3:QUAT 108 1392 -2.02312 0.222693 0.0373699 -0.00179102 0.00138035 0.920068 0.391753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.06164e-05 0.00927855 4.00006 0.00123094 0.613908 +EDGE_SE3:QUAT 109 1392 -5.7165 2.07373 0.0143471 -0.00453159 0.00138065 0.810635 0.585532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 0.000194884 0.0269887 4.00015 0.0125438 1.37164 +EDGE_SE3:QUAT 1393 1394 4.13826 -0.524232 0.00897793 -0.00260035 0.0022921 -0.136983 0.990567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.67101e-05 0.0136021 3.99999 -0.000822349 3.92499 +EDGE_SE3:QUAT 105 1393 5.32572 2.2048 0.0358589 0.00531542 0.00692798 -0.973739 0.2275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -4.06977e-05 0.0234985 4.00063 0.0150214 0.207236 +EDGE_SE3:QUAT 106 1393 1.76231 1.06903 0.00418498 0.00504081 0.0135351 -0.998741 0.0480433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000303412 0.0202498 3.99984 0.0519002 0.0100105 +EDGE_SE3:QUAT 107 1393 -1.88783 1.43292 0.027962 5.76549e-05 -0.0152281 0.982267 0.186868 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000294593 -0.00104123 3.99933 0.055574 0.140483 +EDGE_SE3:QUAT 108 1393 -4.8724 3.50478 0.0488529 -0.00274111 -0.00621514 0.896543 0.442906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -7.73303e-05 0.00936676 3.99986 0.0213509 0.784834 +EDGE_SE3:QUAT 1394 1395 4.06299 -0.887173 -0.00125761 0.00191021 0.00144412 -0.212501 0.977158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.37837e-06 0.0155039 3.99998 -0.00179087 3.81943 +EDGE_SE3:QUAT 104 1394 5.16943 1.83 0.000758903 0.000262617 0.00678776 -0.965145 0.261628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.7069e-05 0.00212543 3.99993 0.0221059 0.273932 +EDGE_SE3:QUAT 105 1394 1.38476 0.829232 -0.00333219 0.00607855 0.0106923 -0.99571 0.0917063 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000226083 0.0246867 4.00043 0.037459 0.0341484 +EDGE_SE3:QUAT 106 1394 -2.38444 1.19293 -0.0159584 -0.00550432 -0.0167973 0.995834 0.089454 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000192119 0.0221908 3.99902 0.0697506 0.0333577 +EDGE_SE3:QUAT 107 1394 -5.51865 3.41287 0.081772 -0.000801145 -0.0172607 0.947257 0.32001 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -0.000448696 -0.000872328 3.99952 0.0538557 0.410473 +EDGE_SE3:QUAT 1395 1396 4.18648 -0.984684 -0.0247833 0.00074389 0.000565386 -0.209919 0.977718 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.85157e-07 0.00604627 4 -0.000689296 3.82374 +EDGE_SE3:QUAT 103 1395 5.13867 1.38384 0.018302 0.00213936 0.00788185 -0.97892 0.204082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.6413e-05 0.00961145 4.00005 0.0249469 0.166788 +EDGE_SE3:QUAT 104 1395 1.23271 0.534973 -0.00290927 0.000942666 0.00521838 -0.9987 0.0507051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.87111e-05 0.00379081 3.99992 0.020358 0.0103915 +EDGE_SE3:QUAT 105 1395 -2.77221 0.964886 -0.0374922 -0.00560287 -0.00984783 0.992503 0.121695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000170211 0.0227653 3.99982 0.0433158 0.0598454 +EDGE_SE3:QUAT 106 1395 -6.20729 2.78923 -0.0173729 -0.00336253 -0.0152288 0.954156 0.298904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.000333742 0.0118712 3.99919 0.0550584 0.358255 +EDGE_SE3:QUAT 1396 1397 3.97576 -0.628341 -0.00535626 0.00794413 0.0222141 -0.115066 0.993078 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00832 -0.000715116 0.185411 3.99791 -0.0107668 3.95562 +EDGE_SE3:QUAT 102 1396 5.09957 1.15502 -0.0683843 -0.0112011 0.00783888 -0.992842 0.118647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000567114 -0.0456441 4.00122 0.0407611 0.0572551 +EDGE_SE3:QUAT 103 1396 0.919778 0.586988 -0.0225241 -0.00136963 -0.00769306 0.999954 0.00556091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.97395e-05 0.00547922 3.99979 0.0308302 0.000368844 +EDGE_SE3:QUAT 104 1396 -3.02967 1.08201 -0.0231753 -0.000858834 -0.00464981 0.987054 0.160319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.22786e-05 0.00341191 3.99991 0.0184879 0.1029 +EDGE_SE3:QUAT 105 1396 -6.58433 2.92679 -0.0718489 -0.0040447 -0.00991001 0.944873 0.327263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000119808 0.0157832 3.99958 0.0388859 0.428893 +EDGE_SE3:QUAT 1397 1398 4.42518 -0.365969 0.000401096 0.00276705 -0.00564073 -0.0536828 0.998538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 -9.71226e-05 -0.0431555 3.99989 0.001143 3.98894 +EDGE_SE3:QUAT 101 1397 5.28145 0.939102 0.0423975 0.00554219 0.00762814 -0.99866 0.0508905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000148264 0.0222637 4.00036 0.0280694 0.0106812 +EDGE_SE3:QUAT 102 1397 1.08514 0.821777 0.0213411 0.0111082 0.00100241 -0.999931 0.00360679 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99951 3.39493e-05 0.0444309 4.00197 0.00369144 0.000549034 +EDGE_SE3:QUAT 103 1397 -3.05735 1.26226 -0.0260995 -0.0225456 0.000527068 0.992403 0.120944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99818 0.00140236 0.0921369 4.00786 0.019533 0.0607577 +EDGE_SE3:QUAT 104 1397 -6.60675 2.9134 -0.0224487 -0.0205319 0.00667338 0.961751 0.273075 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9988 0.00238793 0.0918785 4.0068 0.0197423 0.300626 +EDGE_SE3:QUAT 1398 1399 4.22216 -0.166651 0.0137838 0.00499255 -0.00290445 -0.0102361 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -5.79405e-05 -0.0226185 3.99997 0.000115688 3.99971 +EDGE_SE3:QUAT 100 1398 4.83804 0.817434 0.0511754 0.00707123 0.0100528 -0.999859 0.0114069 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000279436 0.0282938 4.00043 0.0395624 0.00111191 +EDGE_SE3:QUAT 101 1398 0.854991 0.859885 0.00440446 0.000410194 -0.00455156 0.999985 0.00300322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.95229e-06 -0.00164085 3.99992 0.0181958 0.000119524 +EDGE_SE3:QUAT 102 1398 -3.32868 1.16266 -0.0696142 -0.00543118 0.00151733 0.998724 0.0501763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 2.79674e-06 0.0218078 4.00048 -0.00385703 0.0101936 +EDGE_SE3:QUAT 1399 1400 4.37823 -0.0927296 0.00623383 0.00100187 -0.00296485 -0.000716405 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -1.20283e-05 -0.0237109 3.99996 8.7043e-06 4.00014 +EDGE_SE3:QUAT 99 1399 5.05626 0.798385 0.0420441 0.00620209 0.00769552 -0.999949 0.00224399 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.00018997 0.0248102 4.00038 0.030676 0.00040925 +EDGE_SE3:QUAT 100 1399 0.633773 0.885939 0.00573223 0.00409068 0.00518084 -0.999978 0.00092751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.46136e-05 0.0163633 4.00016 0.0206946 0.00017744 +EDGE_SE3:QUAT 101 1399 -3.34568 1.05301 0.019138 0.00306999 0.000323181 0.99991 0.0130498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.89848e-06 -0.012283 4.00015 -0.00161271 0.000719562 +EDGE_SE3:QUAT 1400 1401 4.02 -0.0900594 0.00151063 -0.000203521 0.00152902 0.000105022 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.23894e-06 0.0122325 3.99999 6.30945e-07 4.00004 +EDGE_SE3:QUAT 98 1400 4.96329 0.798681 0.00814228 0.00149031 0.00515504 -0.99998 0.00325904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.12436e-05 0.00596156 3.99993 0.0205808 0.000157265 +EDGE_SE3:QUAT 99 1400 0.691753 0.874558 -0.00305034 0.00313626 0.00659989 -0.999972 0.00134704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.29492e-05 0.0125458 3.99998 0.0263665 0.000220403 +EDGE_SE3:QUAT 100 1400 -3.72913 0.972403 -0.0279618 -0.00134017 -0.00426481 0.99999 5.06115e-05 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.28569e-05 0.00536083 3.99996 0.0170598 7.99547e-05 +EDGE_SE3:QUAT 1401 1402 4.09149 -0.0932733 0.00983335 0.000664083 0.00128166 0.000164185 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 3.41048e-06 0.010252 3.99999 8.67764e-07 4.00003 +EDGE_SE3:QUAT 97 1401 5.21669 0.771275 0.0146076 0.00158412 0.00777277 -0.999954 0.00540876 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.15131e-05 0.00633736 3.9998 0.0310198 0.000367634 +EDGE_SE3:QUAT 98 1401 0.966979 0.847108 0.000665781 0.00342621 0.00519724 -0.999974 0.00350911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.09911e-05 0.0137056 4.00008 0.0206932 0.000203266 +EDGE_SE3:QUAT 99 1401 -3.32804 0.937698 -0.0233723 0.00486855 0.00685843 -0.999964 0.0013697 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000133327 0.0194754 4.00019 0.0273832 0.000289771 +EDGE_SE3:QUAT 1402 1403 4.4885 -0.0770272 0.0176782 -0.00481728 -0.00457546 -0.0026053 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 8.7352e-05 -0.0367553 3.99992 4.55185e-05 4.00031 +EDGE_SE3:QUAT 96 1402 5.51846 0.754473 0.0365442 0.00571973 0.00359939 -0.999944 0.00811648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 7.67676e-05 0.0228812 4.00048 0.0140263 0.000443588 +EDGE_SE3:QUAT 97 1402 1.12937 0.815607 0.00774077 0.00313156 0.0070705 -0.999953 0.00585849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.9486e-05 0.0125278 3.99996 0.0281337 0.000374407 +EDGE_SE3:QUAT 98 1402 -3.12228 0.908867 -0.0179145 0.00486196 0.00453927 -0.999969 0.00419328 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.65922e-05 0.0194487 4.0003 0.0179953 0.000245851 +EDGE_SE3:QUAT 1403 1404 4.27632 -0.116334 0.0117292 -0.00119275 -0.0007411 -0.00842713 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.51659e-06 -0.00604878 4 2.56394e-05 3.99973 +EDGE_SE3:QUAT 95 1403 5.45225 0.72015 0.0217228 0.00558448 0.00421038 -0.999915 0.0109792 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 8.72481e-05 0.0223422 4.00044 0.0163487 0.0006738 +EDGE_SE3:QUAT 96 1403 1.02944 0.76137 0.00356993 0.0011492 0.00864928 -0.999947 0.00541643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.28045e-05 0.00459753 3.99972 0.0345438 0.000420982 +EDGE_SE3:QUAT 97 1403 -3.35472 0.849307 0.00449087 -0.00125639 0.0118577 -0.999923 0.00337165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.59006e-05 -0.00502666 3.99946 0.0474603 0.000614989 +EDGE_SE3:QUAT 1404 1405 4.36988 -0.140229 -0.0251525 -0.000999124 0.0136555 -0.00938724 0.999862 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00297 -9.66065e-05 0.109188 3.99926 -0.000517758 4.00263 +EDGE_SE3:QUAT 94 1404 5.55473 0.727457 -0.0534403 -0.0101739 0.00382345 -0.99987 0.0118704 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 -0.00018357 -0.0407031 4.00158 0.0162636 0.001044 +EDGE_SE3:QUAT 95 1404 1.17954 0.7388 -0.00817726 0.00503059 0.00558483 -0.999968 0.00258436 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000111476 0.0201232 4.00028 0.0222377 0.00025157 +EDGE_SE3:QUAT 96 1404 -3.22543 0.829113 0.0122735 -0.000527028 -0.0099491 0.999947 0.00259121 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.8933e-05 0.00210842 3.99961 0.0398047 0.000424114 +EDGE_SE3:QUAT 1405 1406 4.37843 -0.126145 0.0187733 0.00275644 -0.00234481 -0.00253434 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.60326e-05 -0.0186746 3.99998 2.39908e-05 4.00006 +EDGE_SE3:QUAT 93 1405 5.3863 0.711797 0.0480495 0.00650686 0.00746834 -0.999879 0.0120092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000187187 0.0260346 4.00048 0.0292437 0.000960153 +EDGE_SE3:QUAT 94 1405 1.18682 0.743662 0.00744671 0.0035253 0.00482718 -0.99998 0.00208333 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 6.78401e-05 0.0141017 4.00011 0.0192508 0.000159721 +EDGE_SE3:QUAT 95 1405 -3.16925 0.869185 -0.081713 -0.0187376 -0.00681765 0.999777 0.00697993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99861 0.000569339 0.0749491 4.00539 0.0283678 0.00180055 +EDGE_SE3:QUAT 1406 1407 4.19945 -0.122223 0.0180464 0.00493353 0.000311763 -0.00100498 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.34532e-06 0.00255351 4 -1.28112e-06 4 +EDGE_SE3:QUAT 92 1406 5.18091 0.658627 0.0259253 0.00359403 0.0105308 -0.999821 0.0152841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000159634 0.0143838 3.99979 0.0416601 0.00142016 +EDGE_SE3:QUAT 93 1406 1.01528 0.738927 0.00848448 0.00432594 0.00476449 -0.999934 0.00953663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 7.97908e-05 0.0173065 4.00022 0.0187254 0.000526337 +EDGE_SE3:QUAT 94 1406 -3.17868 0.870108 -0.00181723 -0.00138688 -0.0019205 0.999997 0.000638663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.06648e-05 0.00554754 4.00002 0.00768916 2.41061e-05 +EDGE_SE3:QUAT 1407 1408 3.99695 -0.0685413 0.0296404 -0.00144163 -0.00367106 0.00395069 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 2.238e-05 -0.0293008 3.99995 -5.83064e-05 4.00015 +EDGE_SE3:QUAT 91 1407 5.03971 0.525798 0.0369249 0.00600749 0.00871822 -0.999867 0.0124232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000205853 0.0240378 4.0003 0.0342682 0.0010554 +EDGE_SE3:QUAT 92 1407 0.997267 0.644249 0.0159749 0.00404483 0.00566085 -0.999865 0.0148935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 8.9249e-05 0.0161854 4.00015 0.0221508 0.00107546 +EDGE_SE3:QUAT 93 1407 -3.16184 0.778176 -0.00378332 0.004772 -0.000268343 -0.999952 0.00851465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -9.7663e-06 0.0190899 4.00036 -0.00139839 0.0003816 +EDGE_SE3:QUAT 1408 1409 4.25988 -0.0606783 0.0196423 0.000173403 0.00199976 0.00693476 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 2.04993e-06 0.0159828 3.99998 5.54192e-05 3.99987 +EDGE_SE3:QUAT 90 1408 5.47239 0.219539 -0.000104659 -0.00089872 -0.00812681 0.999945 0.00652918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.58689e-05 0.00359542 3.99975 0.0325498 0.000438652 +EDGE_SE3:QUAT 91 1408 1.0297 0.490506 0.0205474 0.00275017 0.00982202 -0.999807 0.0167682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000117439 0.0110073 3.99976 0.0388916 0.00153325 +EDGE_SE3:QUAT 92 1408 -2.98506 0.602387 0.0137626 0.000593875 0.00703289 -0.999787 0.0194098 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.41074e-05 0.00237748 3.99981 0.0280123 0.00170462 +EDGE_SE3:QUAT 93 1408 -7.14679 0.778461 -0.00896522 0.00105405 0.0010362 -0.999914 0.013042 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.12129e-06 0.00421728 4.00001 0.00403312 0.000688893 +EDGE_SE3:QUAT 1409 1410 4.31148 -0.0741179 0.0389895 -0.00450659 -0.0111536 -0.00282882 0.999924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00192 0.000193386 -0.0894169 3.9995 0.00011321 4.00197 +EDGE_SE3:QUAT 89 1409 5.53105 0.0657673 0.0711399 -0.0133294 -0.0057117 0.999456 0.0296335 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 0.000419506 0.0533865 4.0026 0.0259787 0.00439452 +EDGE_SE3:QUAT 90 1409 1.23443 0.349662 0.0196666 0.00325339 0.00835357 -0.99996 0.000308511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000108804 0.0130149 3.99989 0.033407 0.000321737 +EDGE_SE3:QUAT 91 1409 -3.18921 0.410467 0.0180332 0.0049097 0.0098477 -0.999656 0.0238277 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.00019635 0.019659 4.00005 0.0384034 0.00273661 +EDGE_SE3:QUAT 92 1409 -7.17974 0.498385 0.0358604 0.00279128 0.00668263 -0.999647 0.0255724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 7.81689e-05 0.0111776 3.99997 0.0261169 0.00281769 +EDGE_SE3:QUAT 1410 1411 4.12087 -0.244002 0.0355759 -0.00288043 0.0201693 -0.0529483 0.998389 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00628 -0.00073504 0.159065 3.99846 -0.00423419 3.9951 +EDGE_SE3:QUAT 88 1410 5.21553 0.467342 -0.0242104 0.00247995 -0.00635253 0.999831 0.0170614 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -6.57076e-05 -0.00992494 3.99995 0.0250537 0.00134597 +EDGE_SE3:QUAT 89 1410 1.22031 0.389619 -0.003482 -0.00231704 -0.0106252 0.999418 0.0323427 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.18984e-05 0.00928114 3.9996 0.0429869 0.00466824 +EDGE_SE3:QUAT 90 1410 -3.06547 0.405535 0.0343643 0.00794074 -0.0127802 0.999885 0.00207279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000405712 -0.0317699 4.00037 0.0510023 0.000919705 +EDGE_SE3:QUAT 1411 1412 4.24695 -0.463925 0.00543364 -0.000291252 -1.17526e-05 -0.103621 0.994617 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.79643e-08 -0.000452076 4 2.96501e-05 3.95705 +EDGE_SE3:QUAT 87 1411 4.98437 1.67583 0.0164497 0.00236408 0.00348073 -0.998234 0.0592496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.8831e-05 0.00951186 4.00006 0.0126846 0.0141052 +EDGE_SE3:QUAT 88 1411 1.11876 0.863908 0.0359103 -0.0172922 -0.00874971 0.997349 0.07014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99901 0.0010172 0.0696634 4.00392 0.0442917 0.021389 +EDGE_SE3:QUAT 89 1411 -2.85285 0.901436 0.0184708 -0.0219958 -0.0134485 0.996017 0.0853563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99855 0.00191199 0.0889108 4.0057 0.0678826 0.0322881 +EDGE_SE3:QUAT 90 1411 -7.17458 0.669857 0.1496 -0.0113341 -0.0154757 0.998292 0.0551749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000733022 0.0455402 4.00064 0.0664501 0.0138035 +EDGE_SE3:QUAT 1412 1413 4.18277 -0.761056 0.00317041 0.00256305 0.000446674 -0.191112 0.981565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.56484e-06 0.00911425 3.99999 -0.00105156 3.85392 +EDGE_SE3:QUAT 86 1412 4.12119 2.59343 0.0226328 0.00346307 0.00860996 -0.983833 0.17885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.00010274 0.0148951 4.00019 0.0269233 0.128197 +EDGE_SE3:QUAT 87 1412 0.718707 1.60746 -0.00131864 -0.00237522 -0.00424067 0.998993 0.0445965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 3.86692e-05 0.00952645 4 0.0177244 0.00805681 +EDGE_SE3:QUAT 88 1412 -3.00359 1.89182 -0.0899438 -0.0165903 -0.0105002 0.984814 0.172498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 0.00132256 0.0688577 4.00231 0.0611861 0.121189 +EDGE_SE3:QUAT 89 1412 -6.93076 2.07366 -0.120598 -0.0204949 -0.0150307 0.981906 0.187653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99944 0.00205056 0.0854741 4.00277 0.0846952 0.144563 +EDGE_SE3:QUAT 1413 1414 3.87889 -0.955237 0.0131276 0.00407397 0.00223555 -0.225034 0.97434 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 7.10455e-06 0.027174 3.99995 -0.003416 3.79762 +EDGE_SE3:QUAT 85 1413 3.2619 2.36428 0.0261569 0.00367396 0.0100379 -0.978277 0.207027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000124178 0.0163226 4.00026 0.0300947 0.171754 +EDGE_SE3:QUAT 86 1413 -0.0410085 1.80831 0.00128894 -0.00244861 -0.00664899 0.999902 0.0121049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.24325e-05 0.00979711 3.99991 0.0268235 0.000790018 +EDGE_SE3:QUAT 87 1413 -3.35364 2.70686 0.009307 -0.00159383 -0.00129389 0.972312 0.233678 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.19009e-05 0.00674377 4.00001 0.0072996 0.218447 +EDGE_SE3:QUAT 1414 1415 4.08842 -0.826766 0.00109623 0.00125231 -0.0075754 -0.161756 0.986801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 -0.000232935 -0.0558607 3.99984 0.00439109 3.89612 +EDGE_SE3:QUAT 83 1414 7.06683 2.1188 0.109831 0.0120539 0.0121268 -0.980328 0.196633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99913 -0.000207864 0.0516565 4.00293 0.0256753 0.155535 +EDGE_SE3:QUAT 84 1414 3.11673 1.83738 0.0386996 0.00613294 0.010616 -0.988367 0.151591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000158639 0.0256585 4.00065 0.0327867 0.092367 +EDGE_SE3:QUAT 85 1414 -0.648295 1.63256 0.0124031 -0.0045716 -0.00689086 0.999788 0.0188786 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000127615 0.018297 4.00012 0.0282314 0.00170864 +EDGE_SE3:QUAT 86 1414 -3.89787 2.87294 0.00931899 -0.00353412 -0.00267756 0.971473 0.237109 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.93515e-05 0.0149925 4.00005 0.0155623 0.225005 +EDGE_SE3:QUAT 1415 1416 4.10289 -0.32851 0.0185181 0.00237073 0.00413603 -0.044256 0.999009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 2.1871e-05 0.0342504 3.99993 -0.000765574 3.99246 +EDGE_SE3:QUAT 82 1415 7.1221 1.36489 0.0226199 0.00219389 0.00851764 -0.998641 0.0513788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.51571e-05 0.00882048 3.99984 0.0329467 0.0108508 +EDGE_SE3:QUAT 83 1415 2.96733 1.31041 0.0178427 0.00291694 0.0109403 -0.999289 0.0359721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000151917 0.0116966 3.99972 0.0427815 0.00566842 +EDGE_SE3:QUAT 84 1415 -0.993204 1.39947 -0.0126062 0.0027832 -0.0091288 0.999907 0.00975687 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000106158 -0.0111358 3.9998 0.0362895 0.000741065 +EDGE_SE3:QUAT 85 1415 -4.70578 2.62775 -0.00690938 0.00413983 -0.00639964 0.983633 0.180023 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -3.36493e-05 -0.0176429 4.00034 0.0177816 0.129798 +EDGE_SE3:QUAT 1416 1417 4.32603 -0.163377 0.019813 0.000791775 -0.00213219 -0.0151915 0.999882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -8.30909e-06 -0.0169075 3.99998 0.000128136 3.99915 +EDGE_SE3:QUAT 81 1416 7.19895 1.25864 0.0246683 0.00428374 0.00586964 -0.999843 0.0161356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.75173e-05 0.0171425 4.00018 0.0229125 0.00124619 +EDGE_SE3:QUAT 82 1416 3.0512 1.27702 0.0284892 0.00595212 0.00637229 -0.999937 0.00713396 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000147907 0.0238113 4.00042 0.0251507 0.00050345 +EDGE_SE3:QUAT 83 1416 -1.13396 1.32682 0.0138592 -0.0064063 -0.0085176 0.999905 0.00874143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000221624 0.0256305 4.00034 0.0345182 0.000767748 +EDGE_SE3:QUAT 84 1416 -5.09539 1.82634 0.0488224 -0.000812757 -0.00623589 0.998501 0.0543705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.48363e-06 0.00325748 3.99985 0.0251114 0.0119854 +EDGE_SE3:QUAT 126 1416 0.562816 7.15025 0.136229 0.0103999 0.00612502 -0.488018 0.87275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00132 -0.00072921 0.0838505 3.99983 -0.0235609 3.04911 +EDGE_SE3:QUAT 1417 1418 3.99778 -0.0669883 0.0233761 -0.000855413 -0.000588502 0.00794196 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.03115e-06 -0.00462605 4 -1.82685e-05 3.99975 +EDGE_SE3:QUAT 80 1417 6.87306 1.22481 0.0171508 0.00333305 0.00452096 -0.999981 0.00266638 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 5.99997e-05 0.0133327 4.0001 0.0180134 0.000153996 +EDGE_SE3:QUAT 81 1417 2.87089 1.29284 0.00332225 0.00209022 0.00503648 -0.999985 0.000806859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.21886e-05 0.0083612 3.99997 0.0201326 0.000121412 +EDGE_SE3:QUAT 82 1417 -1.27777 1.37321 -0.0110608 -0.00374075 -0.00595123 0.999939 0.00854894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.94037e-05 0.0149653 4.00007 0.0240577 0.00049303 +EDGE_SE3:QUAT 83 1417 -5.4215 1.58264 -0.0197477 -0.0042836 -0.00801628 0.999679 0.0236649 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000134411 0.0171495 4 0.0328326 0.00258331 +EDGE_SE3:QUAT 126 1417 2.67889 3.38234 0.0557041 0.00974785 0.00392563 -0.501565 0.865056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00081 -0.000416741 0.0691829 3.99984 -0.0208855 2.99493 +EDGE_SE3:QUAT 127 1417 -3.48127 3.16673 0.019483 0.00581495 0.00339251 -0.24531 0.969421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -4.04615e-06 0.0411613 3.99989 -0.00564028 3.75971 +EDGE_SE3:QUAT 1418 1419 4.14463 -0.0393857 0.0114906 -0.000714769 0.00509848 0.0124386 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 -6.83816e-06 0.0408888 3.9999 0.000254123 3.9998 +EDGE_SE3:QUAT 79 1418 7.15437 0.684007 -0.0384769 0.00363915 -0.00531354 0.999462 0.0321699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -7.31067e-05 -0.014581 4.00013 0.0202649 0.00429559 +EDGE_SE3:QUAT 80 1418 2.85937 1.26601 0.01198 0.00297226 0.00557554 -0.999924 0.0106077 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 6.65613e-05 0.0118916 4.00003 0.0220445 0.000606952 +EDGE_SE3:QUAT 81 1418 -1.1153 1.34834 0.0201946 0.00175086 0.00582135 -0.999944 0.00865152 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.2428e-05 0.00700459 3.99992 0.0231599 0.000445769 +EDGE_SE3:QUAT 82 1418 -5.25665 1.49914 -0.00874357 0.00371904 0.00644794 -0.999972 0.000100308 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.59314e-05 0.014877 4.00006 0.0257902 0.000221649 +EDGE_SE3:QUAT 126 1418 4.60777 -0.131813 0.0181042 0.00891704 0.00381565 -0.493921 0.869453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 -0.000360167 0.0643374 3.99986 -0.0189928 3.0252 +EDGE_SE3:QUAT 127 1418 0.0111949 1.20955 0.00691832 0.00471988 0.00289872 -0.236937 0.971509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -2.79475e-06 0.0341839 3.99992 -0.00449717 3.77573 +EDGE_SE3:QUAT 128 1418 -4.38603 0.512568 -0.0717947 0.00211321 -0.00563905 -0.0444747 0.998992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -7.84283e-05 -0.0438565 3.99988 0.000967757 3.99257 +EDGE_SE3:QUAT 1419 1420 4.25272 -0.0623232 -0.00338636 -0.00164912 0.00471904 0.00457618 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 -2.87818e-05 0.0378445 3.99991 8.57953e-05 4.00027 +EDGE_SE3:QUAT 78 1419 7.20816 -1.60766 -0.0570491 0.00491885 -0.0096964 0.969387 0.245296 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -2.71033e-05 -0.022513 4.00061 0.0240093 0.24098 +EDGE_SE3:QUAT 79 1419 3.04676 0.986134 0.00234728 -0.00159044 -0.00606719 0.999792 0.0193908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.38398e-05 0.00636532 3.99988 0.0244924 0.00166417 +EDGE_SE3:QUAT 80 1419 -1.24457 1.22408 -0.00135448 0.00838478 0.00646725 -0.999668 0.0234864 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 0.000183441 0.0335678 4.00102 0.0242679 0.00263558 +EDGE_SE3:QUAT 81 1419 -5.21113 1.33751 0.00938378 0.00742143 0.00680546 -0.999715 0.0216438 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 0.000180071 0.0297079 4.00075 0.0259131 0.00226249 +EDGE_SE3:QUAT 127 1419 3.64883 -0.737565 -0.0202658 0.00506567 0.00805767 -0.224798 0.974359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 -0.000244479 0.072863 3.99971 -0.00850796 3.79919 +EDGE_SE3:QUAT 128 1419 -0.28855 0.108658 -0.00878978 0.00145226 -0.00052125 -0.0315322 0.999502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.65543e-06 -0.00361462 4 5.40756e-05 3.99603 +EDGE_SE3:QUAT 129 1419 -4.25322 0.0291621 -0.0296366 0.000742225 -0.00404918 0.0165834 0.999854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -5.5217e-06 -0.0325296 3.99993 -0.000269849 3.99916 +EDGE_SE3:QUAT 1420 1421 4.34354 -0.116002 0.0076474 -0.0013673 0.000761475 -0.00572788 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.15655e-06 0.00599752 4 -1.71052e-05 3.99988 +EDGE_SE3:QUAT 78 1420 3.50196 0.457363 -0.000399951 -5.09359e-05 -0.010228 0.970526 0.240778 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.00014995 -0.000922682 3.99976 0.0351962 0.23223 +EDGE_SE3:QUAT 79 1420 -1.20034 1.2014 -0.0192384 -0.00639001 -0.00768254 0.999848 0.0143113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000203074 0.0255697 4.00038 0.0314517 0.00123005 +EDGE_SE3:QUAT 80 1420 -5.47967 1.09153 -0.0765546 0.0133338 0.00849214 -0.999483 0.0280143 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99924 0.000345031 0.0533979 4.0027 0.0309457 0.00409213 +EDGE_SE3:QUAT 128 1420 3.96256 -0.221806 -0.012841 -0.000109956 0.00421186 -0.0268287 0.999631 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 -1.32373e-05 0.0336252 3.99993 -0.000450869 3.9974 +EDGE_SE3:QUAT 129 1420 -0.00569833 0.120875 0.000508692 -0.000958139 0.000569793 0.0213769 0.999771 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.15806e-06 0.00480093 4 5.21711e-05 3.99818 +EDGE_SE3:QUAT 130 1420 -4.30764 0.247273 -0.003204 0.000596636 0.000281349 0.0108905 0.99994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.59866e-07 0.00217242 4 1.16882e-05 3.99953 +EDGE_SE3:QUAT 1421 1422 4.15025 -0.107698 0.0188875 0.00145564 -0.000818117 0.000147188 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.76368e-06 -0.0065475 4 -4.58527e-07 4.00001 +EDGE_SE3:QUAT 77 1421 5.45535 0.824247 0.0463938 -0.00457637 -0.0121151 0.833724 0.55203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 -0.000274333 0.00825843 3.99977 0.0298285 1.21939 +EDGE_SE3:QUAT 78 1421 -0.27008 2.58844 0.0318162 -0.00105007 -0.0116752 0.969188 0.246043 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000186869 0.00317114 3.99959 0.0417246 0.242619 +EDGE_SE3:QUAT 79 1421 -5.51444 1.46422 -0.0695863 -0.00750762 -0.00853314 0.999727 0.0203949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000270409 0.0300516 4.00055 0.0353306 0.00220179 +EDGE_SE3:QUAT 129 1421 4.34147 0.176223 -0.00527192 -0.00254266 0.00139894 0.0157882 0.999871 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.42461e-05 0.011669 3.99999 9.32467e-05 3.99904 +EDGE_SE3:QUAT 130 1421 0.0153649 0.228225 0.0038884 -0.000841761 0.00115577 0.00575718 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -3.7376e-06 0.00930387 3.99999 2.68105e-05 3.99989 +EDGE_SE3:QUAT 131 1421 -4.16901 0.386087 -0.0178393 -0.00117603 0.000480458 -0.00861933 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.20985e-06 0.0037216 4 -1.58697e-05 3.99971 +EDGE_SE3:QUAT 191 1421 5.74403 -2.7701 0.00101578 -0.00322761 -0.00297298 0.965465 0.260495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.37721e-05 0.0137363 4.00001 0.0161932 0.271549 +EDGE_SE3:QUAT 192 1421 0.15712 -3.86036 0.0464705 -0.00161153 0.00664214 0.886218 0.463218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 7.03573e-05 0.0134451 4.00023 -0.00875128 0.858386 +EDGE_SE3:QUAT 193 1421 -5.27482 -2.8119 0.203069 0.00796383 0.0170926 0.785881 0.61809 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99925 -0.000549541 -0.0118733 3.99963 -0.0370035 1.52906 +EDGE_SE3:QUAT 832 1421 6.22875 3.17261 0.122172 0.0133667 -0.00657399 -0.711476 0.702552 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000153273 0.0573697 3.99947 -0.0382678 1.97595 +EDGE_SE3:QUAT 833 1421 2.04216 3.21513 0.0229254 0.00326355 0.00301023 -0.715616 0.69848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -0.000196939 0.0266652 4.00012 -0.00913165 1.95173 +EDGE_SE3:QUAT 834 1421 -2.03992 3.28676 0.0254475 0.00203997 0.00896005 -0.718753 0.695204 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -0.000536355 0.0356211 4.00048 -0.00500935 1.93372 +EDGE_SE3:QUAT 835 1421 -6.1294 3.40441 0.209766 -0.00769711 0.0218773 -0.720503 0.693064 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99885 -1.62259e-06 0.0147585 4.00048 0.0246352 1.92259 +EDGE_SE3:QUAT 1422 1423 4.40083 -0.0707191 0.0140953 -0.00451711 -0.00102212 0.00152721 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.82559e-05 -0.00809393 4 -6.27097e-06 4.00001 +EDGE_SE3:QUAT 77 1422 3.94596 4.65981 0.0821573 -0.0033042 -0.0114385 0.833812 0.55192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 -0.000184351 0.00234967 3.99992 0.0250532 1.21879 +EDGE_SE3:QUAT 78 1422 -3.85106 4.65639 0.063569 0.000140927 -0.0102673 0.96914 0.246299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000152876 -0.00184104 3.99979 0.0347137 0.24298 +EDGE_SE3:QUAT 130 1422 4.16373 0.185473 0.00586748 0.00074596 0.000265258 0.00579532 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.75053e-07 0.00207008 4 5.9494e-06 3.99987 +EDGE_SE3:QUAT 131 1422 -0.00577884 0.218271 -0.00260419 0.00023658 -0.000449241 -0.00872358 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.62952e-07 -0.00356875 4 1.55307e-05 3.9997 +EDGE_SE3:QUAT 132 1422 -4.3118 0.258163 -0.00458643 0.00565074 0.00105858 -0.00634038 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 2.53592e-05 0.00889764 3.99999 -2.84967e-05 3.99986 +EDGE_SE3:QUAT 190 1422 6.25266 0.880058 0.0301504 -0.0036203 -0.00782949 0.997762 0.0663003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.42529e-05 0.0145594 3.99988 0.0328866 0.0179076 +EDGE_SE3:QUAT 191 1422 2.21522 -0.587336 -0.00188087 -0.00204859 -0.00175497 0.965403 0.260748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.83409e-05 0.00873781 4.00001 0.00983836 0.272003 +EDGE_SE3:QUAT 192 1422 -2.12114 -0.391852 0.0172378 -0.000338842 0.00753858 0.886176 0.463287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -8.27035e-06 0.00771328 4.00012 -0.0142657 0.858656 +EDGE_SE3:QUAT 193 1422 -6.13797 1.2283 0.181667 0.00954776 0.0179259 0.785817 0.618125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99916 -0.000720001 -0.0190739 3.9994 -0.0424497 1.52949 +EDGE_SE3:QUAT 832 1422 6.07596 -0.990398 0.0905898 0.0140091 -0.00812321 -0.711435 0.702565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000303512 0.0566986 3.99935 -0.0401462 1.97611 +EDGE_SE3:QUAT 833 1422 1.83838 -0.941665 -0.000338637 0.00352988 0.00158073 -0.715568 0.698532 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -0.000128646 0.0242751 4.00006 -0.00999226 1.95199 +EDGE_SE3:QUAT 834 1422 -2.2832 -0.848545 -0.018855 0.00227086 0.00767237 -0.718699 0.695275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -0.000450517 0.0334718 4.00039 -0.0057985 1.93404 +EDGE_SE3:QUAT 835 1422 -6.40279 -0.736351 0.147612 -0.00715144 0.0200416 -0.720706 0.692914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99903 1.76839e-05 0.0129187 4.00038 0.0228883 1.92156 +EDGE_SE3:QUAT 1423 1424 4.15721 -0.0864854 0.0140122 -0.00201766 -0.00806045 0.00112054 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00102 6.68214e-05 -0.0644706 3.99974 -3.92855e-05 4.00103 +EDGE_SE3:QUAT 131 1423 4.38365 0.0693851 0.00700322 -0.00434951 -0.00137561 -0.00717497 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.46727e-05 -0.0113782 3.99999 4.10584e-05 3.99983 +EDGE_SE3:QUAT 132 1423 0.109013 0.131854 -0.00246475 0.00102808 4.04727e-05 -0.00485175 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.07203e-07 0.000383624 4 -9.78961e-07 3.99991 +EDGE_SE3:QUAT 133 1423 -4.20829 0.19428 0.0380162 0.0030301 0.00731017 0.00123486 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 9.0158e-05 0.0584464 3.99979 3.99799e-05 4.00085 +EDGE_SE3:QUAT 189 1423 5.7223 1.768 0.0857488 -0.0100476 -0.0197834 0.999751 0.00229761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9996 0.000793894 0.0402126 4.00003 0.0793454 0.00199903 +EDGE_SE3:QUAT 190 1423 1.90966 1.52724 0.0143516 -0.00309464 -0.0125677 0.997826 0.0646268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.9789e-05 0.0124309 3.99942 0.0513368 0.0174069 +EDGE_SE3:QUAT 191 1423 -1.53484 1.68422 -0.000763433 -0.00257612 -0.00682555 0.965808 0.259157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.21065e-05 0.0103389 3.9998 0.0278087 0.268883 +EDGE_SE3:QUAT 192 1423 -4.55288 3.2358 -0.00143504 -0.00182707 0.0027174 0.886951 0.461853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.33951e-05 0.0113891 4.0001 -0.000217049 0.853274 +EDGE_SE3:QUAT 833 1423 1.64725 -5.31501 -0.0185248 -0.000217459 0.00416778 -0.714387 0.699739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.59143e-05 0.0101936 4.00006 0.000867866 1.9586 +EDGE_SE3:QUAT 834 1423 -2.51722 -5.22736 -0.0684068 -0.00166508 0.0102911 -0.717431 0.696551 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -0.000204714 0.0184071 4.00028 0.00564854 1.94104 +EDGE_SE3:QUAT 1424 1425 4.01811 -0.0835901 0.00647509 0.00122664 0.00280931 0.00245139 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 1.42191e-05 0.0224388 3.99997 2.77223e-05 4.0001 +EDGE_SE3:QUAT 132 1424 4.23619 0.0157886 0.0121534 -0.00114135 -0.00783151 -0.00351189 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00098 3.06435e-05 -0.0627124 3.99975 0.000108535 4.00093 +EDGE_SE3:QUAT 133 1424 -0.0773032 0.115336 -0.00582704 0.00106404 -0.000696048 0.00236336 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.95616e-06 -0.00559851 4 -6.61506e-06 3.99999 +EDGE_SE3:QUAT 134 1424 -4.27869 0.241757 -0.0242768 -0.000247774 -0.00270568 -0.00128836 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 2.45606e-06 -0.0216498 3.99997 1.39047e-05 4.00011 +EDGE_SE3:QUAT 188 1424 5.62551 1.78264 0.0379915 0.00306565 0.0176189 -0.99984 0.000885466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000217945 0.0122683 3.99891 0.0704465 0.00128176 +EDGE_SE3:QUAT 189 1424 1.58811 1.86105 0.0232974 -0.00210148 -0.0217114 0.999762 0.000920911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000178967 0.0084118 3.99818 0.0868426 0.00190733 +EDGE_SE3:QUAT 190 1424 -2.14879 2.1475 0.0179707 0.00469599 -0.0152576 0.997864 0.0633502 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000350878 -0.0189339 3.99966 0.0580528 0.0169893 +EDGE_SE3:QUAT 191 1424 -5.06221 3.80626 0.0121422 0.00462613 -0.0106409 0.966017 0.25822 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 -4.99616e-05 -0.0217249 4.00059 0.0267232 0.267042 +EDGE_SE3:QUAT 1425 1426 4.2085 -0.0806619 0.0237718 0.00238313 -0.0002627 0.00337576 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.65148e-06 -0.00219808 4 -3.76016e-06 3.99996 +EDGE_SE3:QUAT 133 1425 3.92896 0.0661189 -0.00214478 0.00190208 0.00212656 0.00472247 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.65506e-05 0.0169043 3.99998 4.0036e-05 3.99998 +EDGE_SE3:QUAT 134 1425 -0.26575 0.153544 -0.000306286 0.000590881 9.3304e-05 0.0011135 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.17644e-07 0.000738535 4 4.09837e-07 4 +EDGE_SE3:QUAT 135 1425 -4.29947 0.296251 -0.0206353 -0.0020729 0.000775768 -0.00888164 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -6.24731e-06 0.00598446 4 -2.62762e-05 3.99969 +EDGE_SE3:QUAT 187 1425 5.6485 1.77811 0.0385486 0.0066827 0.0140161 -0.999876 0.00269508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000376056 0.0267383 3.99994 0.0559276 0.000989718 +EDGE_SE3:QUAT 188 1425 1.62617 1.86808 0.0193129 0.0059691 0.0165866 -0.999839 0.00332561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000400421 0.0238862 3.99949 0.0661901 0.00128224 +EDGE_SE3:QUAT 189 1425 -2.39775 1.94327 0.0175462 0.00498538 0.0204495 -0.999777 0.00150854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000411729 0.0199539 3.99873 0.0817314 0.0017791 +EDGE_SE3:QUAT 190 1425 -6.13093 2.72937 0.0700599 0.00191385 -0.0140172 0.998006 0.0615198 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000190491 -0.00772803 3.99937 0.054598 0.015902 +EDGE_SE3:QUAT 1426 1427 4.05138 -0.0724202 0.0300052 -0.000761701 -0.000635275 0.00346045 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.95265e-06 -0.00505048 4 -8.72752e-06 3.99996 +EDGE_SE3:QUAT 134 1426 3.90011 0.0805854 0.0174307 0.00301784 -0.000185488 0.0046981 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -2.57664e-06 -0.00165397 4 -4.01547e-06 3.99991 +EDGE_SE3:QUAT 135 1426 -0.107558 0.138366 6.45111e-06 0.000361132 0.000602104 -0.00532919 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.28558e-07 0.00483973 4 -1.29131e-05 3.99989 +EDGE_SE3:QUAT 136 1426 -4.21958 0.240003 -0.0485494 0.00108103 -0.000501309 -0.0100502 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.1309e-06 -0.00387949 4 1.92817e-05 3.9996 +EDGE_SE3:QUAT 186 1426 5.51494 1.7511 0.0363511 0.00581692 0.0110206 -0.999897 0.00714044 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000257419 0.0232732 4.00008 0.0437504 0.000817873 +EDGE_SE3:QUAT 187 1426 1.41535 1.82893 0.0131421 0.00660666 0.0116872 -0.999891 0.00617852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 0.000309056 0.0264329 4.00017 0.0464261 0.000866181 +EDGE_SE3:QUAT 188 1426 -2.56394 1.91982 -0.00136204 0.00590355 0.0142833 -0.999857 0.00685093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000342523 0.0236226 3.99977 0.0568087 0.00113409 +EDGE_SE3:QUAT 189 1426 -6.59273 2.02134 0.00203768 0.00488974 0.0185859 -0.999804 0.00479785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000373771 0.0195697 3.99902 0.0741492 0.00156265 +EDGE_SE3:QUAT 1427 1428 4.27456 -0.0863521 0.0264765 0.00159377 0.00796378 0.00218842 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.001 5.40981e-05 0.0636818 3.99975 7.21364e-05 4.00099 +EDGE_SE3:QUAT 135 1427 3.93202 0.0228907 0.0217357 -0.00043112 -1.2254e-05 -0.00183442 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.38515e-08 -0.000107521 4 1.01519e-07 3.99999 +EDGE_SE3:QUAT 136 1427 -0.157189 0.068424 -0.0103712 0.000400829 -0.00116334 -0.00648488 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.06626e-06 -0.00927497 3.99999 3.00525e-05 3.99985 +EDGE_SE3:QUAT 137 1427 -4.27033 -0.200563 -0.121854 0.000519778 -0.00922667 0.0460798 0.998895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00136 7.51662e-05 -0.0738874 3.99966 -0.00170322 3.99287 +EDGE_SE3:QUAT 185 1427 5.95844 1.66711 -0.019098 -0.000659146 0.0102366 -0.999911 0.00856992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.98603e-05 -0.00263716 3.99959 0.0409822 0.000715471 +EDGE_SE3:QUAT 186 1427 1.48644 1.76817 0.0246752 0.00542766 0.0119758 -0.999863 0.0100214 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000264035 0.0217183 3.99993 0.0474607 0.00108281 +EDGE_SE3:QUAT 187 1427 -2.60198 1.86901 -0.0109616 0.00616619 0.0127166 -0.999854 0.00960481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000316925 0.0246736 4 0.0503878 0.00115597 +EDGE_SE3:QUAT 188 1427 -6.59096 1.94064 -0.0195365 0.00557256 0.0153252 -0.999809 0.0107323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000353135 0.0223017 3.9996 0.0608086 0.00150965 +EDGE_SE3:QUAT 1428 1429 4.0201 -0.0809439 0.00838509 0.000774624 0.00131618 0.00159573 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.13678e-06 0.0105146 3.99999 8.41757e-06 4.00002 +EDGE_SE3:QUAT 136 1428 4.10083 -0.0751169 0.0250144 0.00206783 0.0068102 -0.00446304 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00073 5.15316e-05 0.0545993 3.99981 -0.00011967 4.00067 +EDGE_SE3:QUAT 137 1428 0.00223756 0.124031 -0.00914875 0.00174565 -0.00127881 0.0482335 0.998834 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -7.8765e-06 -0.0112036 3.99999 -0.000277955 3.99073 +EDGE_SE3:QUAT 138 1428 -4.17201 -0.714692 -0.0573493 0.00447406 -0.00477061 0.223944 0.97458 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 6.29778e-05 -0.0469567 3.99987 -0.00559299 3.79995 +EDGE_SE3:QUAT 184 1428 6.02265 1.55295 -0.00190506 -6.53141e-05 0.0108655 -0.999911 0.007791 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.51989e-06 -0.000261206 3.99953 0.0434569 0.000715026 +EDGE_SE3:QUAT 185 1428 1.65751 1.67086 0.0208075 0.00772425 0.00886459 -0.999875 0.0106041 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000265072 0.0309047 4.00068 0.0348036 0.000991372 +EDGE_SE3:QUAT 186 1428 -2.7589 1.76625 -0.00404574 0.0136067 0.0106451 -0.999776 0.0122082 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99923 0.000536215 0.054442 4.00259 0.0412763 0.00176297 +EDGE_SE3:QUAT 187 1428 -6.86171 1.86689 -0.038401 0.0141319 0.0113577 -0.999768 0.0115889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99917 0.000598712 0.0565428 4.00277 0.0441519 0.00182364 +EDGE_SE3:QUAT 1429 1430 4.02752 -0.0784492 0.00161242 -0.000575947 3.56643e-06 0.00171515 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.27668e-08 4.03853e-05 4 3.80221e-08 3.99999 +EDGE_SE3:QUAT 137 1429 4.02858 0.419684 0.00941058 0.00224115 0.000181311 0.0497969 0.998757 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.78484e-07 0.000108077 4 -8.46878e-06 3.99008 +EDGE_SE3:QUAT 138 1429 -0.510352 0.969646 0.00315369 0.00483011 -0.00325539 0.225318 0.974268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00024 4.98979e-06 -0.0367051 3.99991 -0.00454613 3.79726 +EDGE_SE3:QUAT 139 1429 -4.78095 -0.126832 0.00337432 0.00470016 -0.0028984 0.426252 0.904588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00028 0.000115422 -0.0382966 3.99994 -0.00932611 3.2736 +EDGE_SE3:QUAT 183 1429 6.04471 1.51414 0.0232899 0.000789623 0.0128617 -0.99984 0.0123672 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.66803e-05 0.00316039 3.99936 0.051345 0.00127357 +EDGE_SE3:QUAT 184 1429 1.97085 1.57422 0.0075703 0.00138992 0.0102548 -0.999903 0.00937091 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.4369e-05 0.0055614 3.99962 0.0409044 0.000777357 +EDGE_SE3:QUAT 185 1429 -2.35608 1.67545 -0.0308414 0.00916913 0.00822822 -0.999854 0.0118404 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 0.000283952 0.0366861 4.00112 0.032047 0.001154 +EDGE_SE3:QUAT 186 1429 -6.78895 1.74716 -0.0971325 0.0151528 0.0098011 -0.999741 0.0139003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99905 0.000528108 0.0606288 4.00339 0.0375469 0.0020443 +EDGE_SE3:QUAT 1430 1431 4.16351 -0.0969986 0.0175407 0.00220307 -0.000984547 -0.0024 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.63798e-06 -0.00781283 4 9.40066e-06 3.99999 +EDGE_SE3:QUAT 138 1430 3.15375 2.66803 0.0407377 0.00435115 -0.00337392 0.226969 0.973886 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 1.6836e-05 -0.0363789 3.99992 -0.00449294 3.79427 +EDGE_SE3:QUAT 139 1430 -2.16737 2.89807 0.0371919 0.00412683 -0.00305365 0.427387 0.904054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00027 0.000121234 -0.036642 3.99995 -0.00876543 3.2697 +EDGE_SE3:QUAT 140 1430 -6.9897 1.37015 0.0569079 0.00123564 0.00275563 0.580985 0.813909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.43066e-05 0.00521003 4.00001 -0.000635045 2.64982 +EDGE_SE3:QUAT 182 1430 6.13781 1.54465 0.00366774 0.00119375 0.0117937 -0.999458 0.0307026 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.84224e-05 0.00478582 3.99949 0.0467682 0.00432374 +EDGE_SE3:QUAT 183 1430 2.01386 1.48261 0.0189217 0.000753715 0.0133824 -0.999809 0.0142522 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.0406e-05 0.00301716 3.9993 0.0534122 0.00152826 +EDGE_SE3:QUAT 184 1430 -2.0427 1.57177 0.000718448 0.00142923 0.0107405 -0.999881 0.0110021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 7.08803e-05 0.00571915 3.99958 0.0428215 0.00095088 +EDGE_SE3:QUAT 185 1430 -6.38481 1.65768 -0.100682 0.00939127 0.00860193 -0.999826 0.0136004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99963 0.000301803 0.0375776 4.00117 0.0333856 0.00137157 +EDGE_SE3:QUAT 1431 1432 4.30152 -0.110267 0.0129347 -0.0114672 0.000760951 -0.027107 0.999566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 -6.44118e-06 0.00235176 4 -1.50298e-05 3.99706 +EDGE_SE3:QUAT 139 1431 0.540214 6.03912 0.0926914 0.00641468 -0.00292981 0.425287 0.905031 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 0.000128147 -0.046171 3.9999 -0.0115809 3.27705 +EDGE_SE3:QUAT 181 1431 5.95726 1.64584 0.00453604 0.00196855 0.0060191 -0.99786 0.0650828 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.6697e-05 0.00793773 3.99996 0.0228016 0.0170895 +EDGE_SE3:QUAT 182 1431 2.01216 1.37988 0.0132621 0.000167234 0.00984406 -0.999561 0.0279607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.80819e-05 0.000671749 3.99962 0.0392601 0.00351299 +EDGE_SE3:QUAT 183 1431 -2.13677 1.46261 0.0327875 -0.000127972 0.011448 -0.999867 0.0116004 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.30386e-06 -0.000511809 3.99948 0.0457856 0.00106256 +EDGE_SE3:QUAT 184 1431 -6.19262 1.58612 0.00849458 0.000468012 0.00869649 -0.99993 0.00805561 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.10909e-05 0.00187252 3.9997 0.0347489 0.000562362 +EDGE_SE3:QUAT 1432 1433 4.33261 -0.372593 0.0210474 0.00250376 -0.00649112 -0.0943623 0.995514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00056 -0.0001452 -0.048424 3.99987 0.00223235 3.96497 +EDGE_SE3:QUAT 180 1432 5.48235 2.13869 0.0910964 0.013466 0.0194374 -0.983085 0.181616 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99863 0.00024177 0.05738 4.00364 0.0525615 0.133524 +EDGE_SE3:QUAT 181 1432 1.69636 1.19885 -0.00383156 0.00187261 0.0176552 -0.999113 0.0381708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000220449 0.00751951 3.99888 0.0697848 0.00706181 +EDGE_SE3:QUAT 182 1432 -2.28124 1.25856 0.0236452 0.000611785 0.0215215 -0.999768 0.000944711 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.61081e-05 0.00244892 3.99815 0.0860613 0.00185756 +EDGE_SE3:QUAT 183 1432 -6.42468 1.47078 0.0489396 -0.000285684 -0.0231676 0.999614 0.0152982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.92252e-05 0.00114187 3.99785 0.0926261 0.00308302 +EDGE_SE3:QUAT 1433 1434 4.12804 -0.743362 -0.00384929 0.00266931 0.00177148 -0.171342 0.985206 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 6.56799e-06 0.0189336 3.99998 -0.00176026 3.88266 +EDGE_SE3:QUAT 179 1433 5.17271 1.85338 0.00899976 0.00364084 0.00962547 -0.970579 0.240565 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 8.24253e-05 0.0168433 4.00033 0.0264483 0.231756 +EDGE_SE3:QUAT 180 1433 1.30933 0.95852 -0.0155773 0.00556092 0.016769 -0.995967 0.0879674 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99972 0.000453995 0.0225996 3.99982 0.0619084 0.0320486 +EDGE_SE3:QUAT 181 1433 -2.6383 1.25332 0.0143026 0.00623939 -0.0149092 0.998273 0.0564717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000399857 -0.0251048 4 0.0563624 0.0137112 +EDGE_SE3:QUAT 182 1433 -6.5989 1.63779 0.0654299 0.00801873 -0.0187835 0.995438 0.0932012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -0.000631388 -0.0326226 4.00035 0.0676065 0.0361688 +EDGE_SE3:QUAT 1434 1435 4.13565 -0.772161 -0.0162739 -0.00621964 0.00505451 -0.178114 0.983977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -0.000119508 0.0255128 3.99998 -0.00182143 3.87326 +EDGE_SE3:QUAT 178 1434 5.14105 1.36633 -0.00851536 0.000245552 0.00101028 -0.97705 0.213007 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.41262e-06 0.00112486 4 0.00319064 0.181491 +EDGE_SE3:QUAT 179 1434 1.18276 0.589263 -0.0259518 0.0046232 0.0080111 -0.997438 0.0709334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000135871 0.0186557 4.00022 0.0290352 0.0204256 +EDGE_SE3:QUAT 180 1434 -2.87618 0.946524 -0.0514114 -0.00500902 -0.0151616 0.996333 0.0840585 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000169851 0.0201807 3.99922 0.0629186 0.0293622 +EDGE_SE3:QUAT 181 1434 -6.64306 2.44371 0.0936685 0.00676066 -0.0109049 0.97396 0.226356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 -7.25369e-06 -0.0300485 4.00106 0.026528 0.205383 +EDGE_SE3:QUAT 1435 1436 3.9336 -0.713284 -0.0114789 0.00479909 0.00703954 -0.161109 0.9869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00091 -7.5779e-05 0.0632686 3.99976 -0.00528174 3.89718 +EDGE_SE3:QUAT 177 1435 5.02353 0.98892 -0.0103554 0.00075875 0.0065966 -0.986981 0.160699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.93585e-05 0.00336963 3.99991 0.0237481 0.103446 +EDGE_SE3:QUAT 178 1435 1.0526 0.318689 -0.02645 0.00380273 0.00819723 -0.999336 0.0353055 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000128868 0.0152435 4.00002 0.031616 0.0052943 +EDGE_SE3:QUAT 179 1435 -3.00546 0.765442 -0.071334 -0.00794681 -0.0152257 0.994019 0.10785 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000365257 0.0321954 3.99952 0.0659192 0.0478858 +EDGE_SE3:QUAT 180 1435 -6.81273 2.4116 -0.0671926 -0.0078301 -0.0214463 0.96531 0.260105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000344515 0.0313144 3.99804 0.0867867 0.272889 +EDGE_SE3:QUAT 1436 1437 4.14484 -0.65144 -0.0385551 0.00435543 0.0138166 -0.121242 0.992517 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0032 -0.000338331 0.114461 3.99921 -0.00701047 3.94447 +EDGE_SE3:QUAT 176 1436 5.2606 0.972978 -0.0483692 -0.00979812 0.00651154 -0.993777 0.110763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000419976 -0.0398412 4.001 0.0338405 0.0497633 +EDGE_SE3:QUAT 177 1436 1.0777 0.398697 -0.0283892 -0.00761031 -0.00325506 0.999966 0.000551507 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99977 9.9886e-05 0.0304409 4.00088 0.0130579 0.000275505 +EDGE_SE3:QUAT 178 1436 -2.90473 0.776164 -0.0558833 -0.00975159 -0.00424021 0.99197 0.126028 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000386722 0.0398597 4.00114 0.0259788 0.0641057 +EDGE_SE3:QUAT 179 1436 -6.68857 2.29225 -0.094984 -0.0116776 -0.0105128 0.963609 0.266852 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.000570562 0.0498473 4.00016 0.0579208 0.28637 +EDGE_SE3:QUAT 1437 1438 4.00433 -0.276245 0.0167635 0.00478511 -0.00649821 -0.0351906 0.999348 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00053 -0.000151155 -0.0498749 3.99985 0.000870057 3.99567 +EDGE_SE3:QUAT 175 1437 5.3589 0.89062 0.0482317 0.00898123 0.00949735 -0.998662 0.0500265 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000267226 0.0360703 4.00113 0.0341818 0.0106296 +EDGE_SE3:QUAT 176 1437 1.07651 0.702044 -0.00017502 -0.00364983 -0.00235937 0.999934 0.0105973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.7305e-05 0.0146018 4.00019 0.0097449 0.000526265 +EDGE_SE3:QUAT 177 1437 -3.04786 1.07302 -0.122678 -0.0207663 0.000430909 0.992353 0.121669 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99846 0.00119991 0.084888 4.00665 0.0183087 0.0611248 +EDGE_SE3:QUAT 178 1437 -6.73942 2.42982 -0.160228 -0.0224959 0.000786443 0.969051 0.245831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99885 0.00265908 0.0978877 4.00688 0.039015 0.244629 +EDGE_SE3:QUAT 1438 1439 4.16382 -0.149904 0.0146043 -0.000684359 0.000186481 -0.0105613 0.999944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.78829e-07 0.00140487 4 -7.26602e-06 3.99955 +EDGE_SE3:QUAT 174 1438 5.34788 0.6966 0.0195124 0.00342181 0.00539578 -0.999726 0.0225128 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 7.21753e-05 0.0136986 4.00009 0.020941 0.00218393 +EDGE_SE3:QUAT 175 1438 1.34882 0.766879 -0.00675729 0.00219314 0.00486823 -0.999874 0.0149415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.36615e-05 0.00877591 3.99999 0.0192003 0.00100444 +EDGE_SE3:QUAT 176 1438 -2.91083 1.06939 -0.0179821 0.00303006 0.0016771 0.998913 0.0464789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.87938e-05 -0.0121581 4.00012 -0.00779681 0.00869342 +EDGE_SE3:QUAT 177 1438 -6.86373 2.33066 -0.271633 -0.0136963 0.00344272 0.987444 0.157336 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99928 0.000547587 0.056884 4.00309 0.00389614 0.0998517 +EDGE_SE3:QUAT 1439 1440 4.20962 -0.119147 0.0245 0.00246211 -0.00236417 -0.00288601 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.3529e-05 -0.0188281 3.99998 2.74573e-05 4.00006 +EDGE_SE3:QUAT 173 1439 5.43584 0.584331 0.0325209 0.0058462 0.00851084 -0.999837 0.0148053 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000194832 0.0233947 4.00029 0.0333378 0.00129153 +EDGE_SE3:QUAT 174 1439 1.16465 0.649832 0.0047554 0.0036766 0.00606308 -0.999909 0.0114883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.86397e-05 0.0147101 4.00008 0.0239079 0.000724941 +EDGE_SE3:QUAT 175 1439 -2.78041 0.80614 -0.0149123 0.00257798 0.00561769 -0.999972 0.00425582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.83098e-05 0.0103126 3.99998 0.0223824 0.000224281 +EDGE_SE3:QUAT 176 1439 -7.01551 1.60171 0.0261836 0.00265632 0.00125994 0.998375 0.0569017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.15641e-05 -0.0106749 4.0001 -0.00620453 0.0129894 +EDGE_SE3:QUAT 1440 1441 4.17023 -0.0698099 0.0214255 -0.0044941 6.42649e-05 0.00259952 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -1.57482e-06 0.000654286 4 9.1049e-07 3.99997 +EDGE_SE3:QUAT 172 1440 5.58834 0.480388 0.0132969 0.00275815 0.00363862 -0.999915 0.012241 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.9112e-05 0.0110353 4.00007 0.0142795 0.000680799 +EDGE_SE3:QUAT 173 1440 1.25824 0.568951 0.000400522 0.00344604 0.00627766 -0.999904 0.0118327 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 8.6704e-05 0.0137879 4.00004 0.0247769 0.000761075 +EDGE_SE3:QUAT 174 1440 -3.01194 0.666914 -0.00811227 0.00125306 0.00411053 -0.999953 0.00868142 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.14239e-05 0.00501294 3.99996 0.016352 0.000374604 +EDGE_SE3:QUAT 175 1440 -6.97634 0.865802 -0.0105764 -3.56729e-05 0.00324971 -0.999994 0.000826215 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.93913e-07 -0.000142694 3.99996 0.012999 4.49794e-05 +EDGE_SE3:QUAT 1441 1442 4.19675 -0.0711301 0.0278722 -0.00206169 -0.00371842 0.00149092 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 3.11136e-05 -0.0297116 3.99994 -2.28256e-05 4.00021 +EDGE_SE3:QUAT 171 1441 5.70192 0.335949 0.0298122 0.00795232 0.00510744 -0.999888 0.0116057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.000147059 0.0318158 4.00093 0.0196913 0.0008888 +EDGE_SE3:QUAT 172 1441 1.39609 0.440541 0.00520628 0.00254973 0.00874106 -0.999857 0.0142635 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.53413e-05 0.0102034 3.99981 0.0346556 0.00114015 +EDGE_SE3:QUAT 173 1441 -2.93581 0.542306 -0.00944413 0.00345067 0.010918 -0.999834 0.0141491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000159647 0.0138095 3.99974 0.0432602 0.00131645 +EDGE_SE3:QUAT 174 1441 -7.15249 0.665206 0.00335757 0.00125955 0.00852333 -0.999904 0.0108372 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.8739e-05 0.00503978 3.99974 0.0339732 0.000764728 +EDGE_SE3:QUAT 1442 1443 4.12068 -0.0872214 0.0103695 0.000989156 0.010783 0.000909253 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00186 4.52647e-05 0.0862881 3.99954 4.20364e-05 4.00186 +EDGE_SE3:QUAT 170 1442 5.92389 0.18767 -0.0559445 -0.00560593 0.00618377 -0.999926 0.0088913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000142523 -0.0224274 4.00034 0.0251327 0.000599883 +EDGE_SE3:QUAT 171 1442 1.51224 0.312323 -0.0048428 0.00432479 0.00686349 -0.999877 0.0134155 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000117445 0.0173049 4.00013 0.0269798 0.000976785 +EDGE_SE3:QUAT 172 1442 -2.7862 0.400535 0.012852 -0.00105432 0.0105801 -0.999819 0.0157804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.07377e-05 -0.00421908 3.99956 0.042425 0.00145066 +EDGE_SE3:QUAT 173 1442 -7.11012 0.502864 -0.011195 -7.33431e-05 0.0129723 -0.999796 0.0155061 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.70587e-05 -0.000292895 3.99933 0.0518626 0.00163448 +EDGE_SE3:QUAT 1443 1444 4.16671 -0.0943611 -0.000377939 0.001178 0.00426674 0.000638207 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 2.03816e-05 0.034127 3.99993 1.14057e-05 4.00029 +EDGE_SE3:QUAT 169 1443 6.06885 0.0572136 0.00209941 -0.00143753 0.00772129 -0.999958 0.00480034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.23268e-05 -0.00575082 3.99979 0.030938 0.000339748 +EDGE_SE3:QUAT 170 1443 1.79847 0.200836 0.0015434 0.00513821 0.0053189 -0.99992 0.0102482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000104996 0.0205566 4.00032 0.0208516 0.000634456 +EDGE_SE3:QUAT 171 1443 -2.61195 0.287729 -0.0292732 0.0149149 0.00616409 -0.999772 0.0139734 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99909 0.000297332 0.0596727 4.00347 0.023005 0.00180378 +EDGE_SE3:QUAT 172 1443 -6.90993 0.358279 0.036762 0.00960366 0.0100145 -0.999768 0.0164753 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000360228 0.0384338 4.00115 0.0387839 0.00183115 +EDGE_SE3:QUAT 1444 1445 4.2536 -0.104796 0.0126211 0.00346651 -0.00492343 0.00150115 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00034 -6.75586e-05 -0.0394524 3.9999 -2.7613e-05 4.00038 +EDGE_SE3:QUAT 168 1444 6.11793 -0.0595446 0.0443158 -0.00722654 -0.00980326 0.999921 0.00295538 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.000284917 0.02891 4.00044 0.0393924 0.000631757 +EDGE_SE3:QUAT 169 1444 1.93359 0.105268 0.0148833 0.00278836 0.00661531 -0.999957 0.0059248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 7.47124e-05 0.0111547 3.99995 0.0263274 0.000344809 +EDGE_SE3:QUAT 170 1444 -2.34256 0.202331 -0.042073 0.00934909 0.00432329 -0.999892 0.0104353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000141254 0.0374017 4.00134 0.0165159 0.000853539 +EDGE_SE3:QUAT 171 1444 -6.73261 0.275983 -0.153626 0.0192833 0.00515748 -0.999687 0.015102 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99849 0.000266696 0.0771466 4.00592 0.0183253 0.00248489 +EDGE_SE3:QUAT 1445 1446 4.32139 -0.109167 0.0208526 0.00298709 -0.00193403 0.00196688 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -2.30717e-05 -0.0155426 3.99998 -1.50388e-05 4.00004 +EDGE_SE3:QUAT 167 1445 6.1726 -0.122407 0.0309354 -0.00518632 -0.00952992 0.999876 0.0113717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000196406 0.0207519 4.00004 0.0385828 0.000997122 +EDGE_SE3:QUAT 168 1445 1.85409 0.0755979 0.00088765 -0.00238783 -0.00622432 0.999977 0.00133648 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.92175e-05 0.00955187 3.99994 0.024923 0.000185244 +EDGE_SE3:QUAT 169 1445 -2.33374 0.165706 0.00911456 -0.00199829 0.00306991 -0.999968 0.00717012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.46656e-05 -0.00799387 4.00002 0.0123929 0.000260016 +EDGE_SE3:QUAT 170 1445 -6.59575 0.237176 -0.107803 0.00466501 0.000397775 -0.99992 0.0117425 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 1.29108e-06 0.0186637 4.00035 0.0011525 0.000638978 +EDGE_SE3:QUAT 1446 1447 4.30953 -0.0868236 0.0208533 0.00107327 -0.00126262 0.00277802 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.33931e-06 -0.0101367 3.99999 -1.40554e-05 3.99999 +EDGE_SE3:QUAT 166 1446 5.93396 -0.0783229 0.0210334 -0.00467739 -0.0070968 0.999791 0.0185969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000134344 0.0187202 4.00012 0.0290608 0.00168222 +EDGE_SE3:QUAT 167 1446 1.84228 0.0778119 0.00692743 -0.00334198 -0.00635928 0.999928 0.00965496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.43543e-05 0.0133705 4.00001 0.0256903 0.000582579 +EDGE_SE3:QUAT 168 1446 -2.46146 0.172219 0.0127351 0.000427024 0.00289925 -0.999996 0.000452567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.98057e-06 0.00170812 3.99997 0.0115954 3.51624e-05 +EDGE_SE3:QUAT 169 1446 -6.63988 0.200725 0.0479644 -0.00370733 -0.000220845 -0.999952 0.00901684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 3.00791e-07 -0.014831 4.00022 -0.000615835 0.000380303 +EDGE_SE3:QUAT 1447 1448 4.14426 -0.0735955 0.0225615 0.000620684 0.000383484 0.00514799 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.53992e-07 0.00302941 4 7.76684e-06 3.9999 +EDGE_SE3:QUAT 165 1447 5.67576 -0.00723464 0.0113765 -0.00357221 -0.00723136 0.999598 0.0271724 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 9.90926e-05 0.0143046 3.99996 0.029649 0.00322446 +EDGE_SE3:QUAT 166 1447 1.64768 0.174153 0.00224904 -0.00345826 -0.00595502 0.999854 0.0156351 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.21154e-05 0.0138386 4.00003 0.024239 0.00117263 +EDGE_SE3:QUAT 167 1447 -2.41748 0.250566 0.00113623 -0.00221222 -0.00567512 0.99996 0.00656878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.92631e-05 0.00884985 3.99995 0.0228145 0.000322308 +EDGE_SE3:QUAT 168 1447 -6.74104 0.262814 0.0252457 -0.000974906 0.00219819 -0.999991 0.00337918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.51705e-06 -0.00389972 4 0.0088189 6.89209e-05 +EDGE_SE3:QUAT 1448 1449 4.29777 -0.0313945 0.0241531 -0.00898123 -0.00408337 0.00558753 0.999936 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000145261 -0.0320611 3.99994 -9.25119e-05 4.00013 +EDGE_SE3:QUAT 164 1448 6.03043 0.300859 0.0326816 -0.00593953 0.000928183 0.999835 0.0171401 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -7.57048e-06 0.0237682 4.00057 -0.00289633 0.00131851 +EDGE_SE3:QUAT 165 1448 1.53041 0.281473 0.00671943 -0.0039611 -0.0068448 0.999733 0.0217125 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000107693 0.0158561 4.00004 0.0280362 0.00214521 +EDGE_SE3:QUAT 166 1448 -2.50718 0.380274 -0.00119574 -0.00406967 -0.00561512 0.999921 0.0104732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.27823e-05 0.016282 4.00013 0.0227969 0.000634965 +EDGE_SE3:QUAT 167 1448 -6.55681 0.373744 0.00138216 -0.00274055 -0.00514377 0.999982 0.00138723 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.63446e-05 0.0109626 4.00001 0.020606 0.000143892 +EDGE_SE3:QUAT 1449 1450 4.08842 -0.102209 0.0165987 -0.00142759 -0.0038176 -0.0172194 0.999843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 1.59613e-05 -0.0308236 3.99994 0.000265725 3.99905 +EDGE_SE3:QUAT 163 1449 5.95926 0.957562 0.0416588 0.00770508 0.00591402 -0.998441 0.05496 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 0.000110924 0.0309671 4.00092 0.0201067 0.0124243 +EDGE_SE3:QUAT 164 1449 1.75272 0.483621 0.00263895 -0.001953 -0.00826459 0.9999 0.0113153 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.92811e-05 0.00781417 3.99978 0.033224 0.000803416 +EDGE_SE3:QUAT 165 1449 -2.74986 0.513148 -0.00299904 -0.000325844 -0.0161745 0.999733 0.0164825 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.34288e-05 0.00130328 3.99895 0.0646884 0.00213382 +EDGE_SE3:QUAT 166 1449 -6.76651 0.497141 -0.0162982 -0.000193326 -0.0152447 0.999871 0.00499394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.50039e-06 0.000773444 3.99907 0.0609758 0.00102966 +EDGE_SE3:QUAT 1450 1451 4.23803 -0.356542 0.0107587 -0.00664041 0.0205962 -0.0901007 0.995698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00588 -0.00135388 0.155813 3.9986 -0.00697283 3.97358 +EDGE_SE3:QUAT 162 1450 5.85281 1.38582 -0.121321 -0.0141622 -0.00137369 -0.989544 0.14353 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99929 -0.000610744 -0.0584017 4.00314 0.0107294 0.0833013 +EDGE_SE3:QUAT 163 1450 1.89469 0.621915 -0.012099 0.00370134 0.00783072 -0.999246 0.0378416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000119334 0.0148416 4.00003 0.0300937 0.00600984 +EDGE_SE3:QUAT 164 1450 -2.32931 0.705999 0.00671164 0.00178971 -0.00991316 0.999533 0.0288363 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -9.0386e-05 -0.00717083 3.99969 0.0391568 0.00372267 +EDGE_SE3:QUAT 165 1450 -6.83396 0.770911 0.0174307 0.00384414 -0.0181788 0.99927 0.0333696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000350428 -0.015416 3.99904 0.0714843 0.00579284 +EDGE_SE3:QUAT 1451 1452 4.21783 -0.759888 -0.00450217 0.00376157 -0.000143499 -0.177009 0.984202 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 1.60555e-05 0.00672859 3.99999 -0.000832705 3.87468 +EDGE_SE3:QUAT 161 1451 5.78719 1.53807 0.0279111 0.0032059 0.0108979 -0.979687 0.200209 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000164474 0.0142716 4.00013 0.0343602 0.160702 +EDGE_SE3:QUAT 162 1451 1.69318 0.514427 0.0145732 0.00536525 0.0067531 -0.99855 0.0531312 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000121079 0.0215604 4.00037 0.0245518 0.0115594 +EDGE_SE3:QUAT 163 1451 -2.35356 0.632682 -0.0284455 -0.0233387 -0.0152914 0.99822 0.0527097 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99816 0.00196235 0.0937601 4.00683 0.0707451 0.0145681 +EDGE_SE3:QUAT 164 1451 -6.53581 1.2863 0.0417269 -0.0178507 -0.0160347 0.992609 0.118959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 0.00154919 0.0727337 4.00238 0.0787197 0.0595074 +EDGE_SE3:QUAT 1452 1453 4.00718 -0.778389 0.00685924 0.00382277 0.00513423 -0.184933 0.98273 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -5.43601e-05 0.0472804 3.99987 -0.00456495 3.86376 +EDGE_SE3:QUAT 160 1452 5.37982 1.69868 -0.00801329 -0.00093576 0.0098557 -0.979814 0.199666 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000109598 -0.00333161 3.99966 0.0369825 0.159826 +EDGE_SE3:QUAT 161 1452 1.60871 0.567927 -0.00494286 0.00178623 0.00743207 -0.999699 0.023298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.11258e-05 0.00715212 3.99985 0.0293551 0.00239954 +EDGE_SE3:QUAT 162 1452 -2.56392 0.821443 -0.0203428 -0.00425882 -0.00341778 0.992224 0.124342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.58342e-05 0.0173737 4.00015 0.0173177 0.0619959 +EDGE_SE3:QUAT 163 1452 -6.4501 1.86464 -0.195568 -0.0198244 -0.0153532 0.973197 0.2286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 0.00187545 0.0838762 4.00174 0.0879862 0.212856 +EDGE_SE3:QUAT 1453 1454 4.11783 -0.853563 -0.00119101 2.44321e-05 0.000951827 -0.186271 0.982498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.75129e-06 0.00727514 4 -0.00066665 3.86123 +EDGE_SE3:QUAT 159 1453 5.25302 2.27599 0.0147045 0.00133923 0.0101299 -0.971104 0.23844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.00014538 0.00689339 3.99993 0.0324682 0.227713 +EDGE_SE3:QUAT 160 1453 1.39743 0.838874 0.0040033 0.00306498 0.00692393 -0.999863 0.0147422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 8.69222e-05 0.0122649 3.99997 0.0273202 0.00109358 +EDGE_SE3:QUAT 161 1453 -2.42678 1.18358 -0.00862531 -0.00593804 -0.00399978 0.986771 0.161965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000168417 0.0245338 4.00029 0.0224547 0.105212 +EDGE_SE3:QUAT 162 1453 -6.24803 2.57151 -0.0468228 -0.00836526 0.000133226 0.952115 0.305626 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.00042953 0.0378453 4.00084 0.0181375 0.374095 +EDGE_SE3:QUAT 1454 1455 4.0696 -0.641098 0.0236781 0.00716441 -0.00628116 -0.11344 0.993499 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -0.000204443 -0.0396122 3.99992 0.00204931 3.94891 +EDGE_SE3:QUAT 158 1454 4.58061 2.34126 0.0410824 0.00693102 0.011724 -0.959118 0.28268 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99953 -0.000133422 0.0329563 4.00131 0.0233815 0.320099 +EDGE_SE3:QUAT 159 1454 1.21955 1.10884 0.00541902 0.000433759 0.0102427 -0.99851 0.0535928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.11115e-05 0.00175581 3.9996 0.0404897 0.0119006 +EDGE_SE3:QUAT 160 1454 -2.73876 1.57348 -0.00900394 -0.00297044 -0.00718411 0.98512 0.171693 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.90853e-05 0.0121051 3.9998 0.0305997 0.118192 +EDGE_SE3:QUAT 161 1454 -6.04299 3.27588 -0.0404674 -0.00610072 -0.00459108 0.939359 0.34285 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000139915 0.0268352 4.00002 0.0279629 0.470587 +EDGE_SE3:QUAT 1455 1456 4.2222 -0.235785 0.0240465 9.86771e-05 0.00054445 -0.0270457 0.999634 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.23349e-08 0.00438284 4 -5.93907e-05 3.99708 +EDGE_SE3:QUAT 157 1455 4.63671 1.8734 -0.00287331 0.00284556 0.00131313 -0.913328 0.407212 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.27037e-05 0.0145529 4.00012 -0.00452686 0.663351 +EDGE_SE3:QUAT 158 1455 0.814509 0.677769 -0.00880068 0.0014857 0.00395568 -0.985006 0.172466 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.27475e-05 0.00636436 4.00003 0.0126698 0.11903 +EDGE_SE3:QUAT 159 1455 -2.90255 1.31877 0.0348415 0.00671931 -0.00296912 0.998165 0.0601011 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -1.47213e-05 -0.027027 4.00074 0.00855231 0.0146502 +EDGE_SE3:QUAT 160 1455 -6.34779 3.54467 0.0195831 0.00557203 -0.00129096 0.959387 0.282035 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000182733 -0.0250171 4.00047 -0.00740785 0.318356 +EDGE_SE3:QUAT 1456 1457 4.24721 -0.0952227 0.0105473 -0.000152269 0.000316926 0.000618953 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.91654e-07 0.00253654 4 7.8475e-07 4 +EDGE_SE3:QUAT 156 1456 6.27449 0.444794 0.005387 -0.000378536 -0.000859419 -0.822822 0.568298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.97331e-06 -0.00331251 4.00001 0.000163636 1.29186 +EDGE_SE3:QUAT 157 1456 1.65724 -1.10927 -0.00807572 0.00346607 0.0015667 -0.923908 0.382595 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.00010086 0.0172616 4.00019 -0.00496163 0.585606 +EDGE_SE3:QUAT 158 1456 -3.22943 -0.534512 -0.00462598 0.00201814 0.00399861 -0.989288 0.145907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 2.47031e-05 0.00842561 4.00006 0.0128444 0.0852156 +EDGE_SE3:QUAT 159 1456 -7.05233 2.05686 0.11324 0.00626143 -0.00256071 0.996192 0.0869225 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 1.97911e-05 -0.0253408 4.00065 0.00572972 0.0303922 +EDGE_SE3:QUAT 1457 1458 4.11729 -0.0598758 0.0182609 0.000470941 -0.00014419 0.00457837 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.77367e-07 -0.00117936 4 -2.71924e-06 3.99992 +EDGE_SE3:QUAT 156 1457 4.67479 -3.47966 0.0247515 0.000174899 -0.000717354 -0.822595 0.568627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.94734e-07 -0.000107495 4 -0.00137235 1.29335 +EDGE_SE3:QUAT 157 1457 -1.41956 -4.01392 -0.0272337 0.00396599 0.0016138 -0.923782 0.382894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000130032 0.0196771 4.00024 -0.00615359 0.586549 +EDGE_SE3:QUAT 1458 1459 4.14776 -0.0904354 -0.00878508 0.00189668 0.00905596 0.00343526 0.999951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 7.54352e-05 0.0723886 3.99967 0.000128126 4.00126 +EDGE_SE3:QUAT 1459 1460 4.31429 -0.0918263 -0.0042769 -0.000607753 -0.0015478 0.00254373 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.90118e-06 -0.0123638 3.99999 -1.57524e-05 4.00001 +EDGE_SE3:QUAT 1460 1461 4.37333 -0.0788884 -0.00873544 0.000413866 -0.00104587 0.00146919 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -1.69481e-06 -0.00837424 4 -6.14263e-06 4.00001 +EDGE_SE3:QUAT 918 1460 3.36163 -4.01027 -0.0180584 -0.000328158 -0.00459792 0.717313 0.696736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 6.19757e-05 -0.0105852 4.00007 0.00132495 1.94183 +EDGE_SE3:QUAT 919 1460 -0.685487 -3.91142 -0.0253431 -0.000222591 -0.00365462 0.716479 0.697599 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.10096e-05 -0.00866661 4.00005 0.000917261 1.94662 +EDGE_SE3:QUAT 920 1460 -4.72648 -3.8182 0.215699 0.0185886 0.015233 0.715415 0.698286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99918 -0.00106379 -0.0635875 3.99862 -0.0542231 1.95329 +EDGE_SE3:QUAT 1461 1462 4.34012 -0.0942681 -0.00302115 -0.0012744 0.00291479 -0.00313658 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.54566e-05 0.0232706 3.99997 -3.67321e-05 4.0001 +EDGE_SE3:QUAT 917 1461 7.31391 0.283487 -0.0558388 0.00427591 2.84415e-05 0.719033 0.694963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 7.66115e-05 -0.0241023 4 -0.012294 1.93211 +EDGE_SE3:QUAT 918 1461 3.31897 0.362715 0.00327353 0.000919664 -0.00489562 0.71823 0.695788 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 0.000147291 -0.0183932 4.00013 -0.00219522 1.93662 +EDGE_SE3:QUAT 919 1461 -0.70904 0.441845 -0.00854569 0.000657658 -0.00425857 0.717705 0.696334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.000103527 -0.0152219 4.0001 -0.00151813 1.93962 +EDGE_SE3:QUAT 920 1461 -4.74058 0.530093 0.215581 0.0189576 0.0144043 0.716692 0.696983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99933 -0.000973256 -0.0681485 3.99861 -0.0554622 1.94618 +EDGE_SE3:QUAT 1382 1461 3.5256 5.12094 0.16128 0.0209596 -0.00579273 -0.4971 0.867421 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99938 0.000744714 0.0741684 3.9992 -0.0301132 3.0127 +EDGE_SE3:QUAT 1383 1461 -3.25558 5.26128 0.0788779 0.0134574 -0.000739464 -0.290677 0.956726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000273004 0.0391142 3.99983 -0.00798511 3.66237 +EDGE_SE3:QUAT 1462 1463 4.01831 -0.0716419 0.0143178 -0.00555429 -0.00148365 0.000346347 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 3.28941e-05 -0.0118456 3.99999 -2.34255e-06 4.00003 +EDGE_SE3:QUAT 918 1462 3.29162 4.69366 0.0370012 -0.00267852 -0.00386749 0.716206 0.697874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -3.73145e-05 0.00463192 3.99997 0.00795827 1.94817 +EDGE_SE3:QUAT 919 1462 -0.73687 4.75807 0.0202396 -0.00210556 -0.00301603 0.71534 0.698767 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.29192e-05 0.00367595 3.99998 0.00622544 1.95314 +EDGE_SE3:QUAT 920 1462 -4.76373 4.87735 0.245995 0.0160687 0.0158887 0.714289 0.699486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99903 -0.00101881 -0.0473359 3.99893 -0.0468499 1.95923 +EDGE_SE3:QUAT 1382 1462 5.63992 1.30913 0.106199 0.0210131 -0.00224818 -0.499695 0.865944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 0.000344726 0.0933654 3.99913 -0.0340851 3.00324 +EDGE_SE3:QUAT 1383 1462 0.310027 2.74175 0.0453116 0.0128239 0.00243056 -0.293669 0.955818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 0.000174291 0.0595823 3.99971 -0.0108106 3.65589 +EDGE_SE3:QUAT 1384 1462 -4.76831 1.99701 0.0562679 0.0104281 0.0046217 -0.113086 0.99352 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 0.000190051 0.0502982 3.99982 -0.00308924 3.94947 +EDGE_SE3:QUAT 1463 1464 4.46728 -0.104763 0.0345597 0.00505653 -0.00497299 0.00338114 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 -9.92807e-05 -0.0399904 3.9999 -6.47131e-05 4.00035 +EDGE_SE3:QUAT 1383 1463 3.58216 0.42705 0.00744167 0.00706628 0.00265065 -0.293354 0.955974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 1.22657e-05 0.0419784 3.99988 -0.00722347 3.65621 +EDGE_SE3:QUAT 1384 1463 -0.890165 1.02097 0.017039 0.00469925 0.00363106 -0.112716 0.993609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 3.85105e-05 0.0348005 3.99992 -0.00206852 3.94948 +EDGE_SE3:QUAT 1385 1463 -5.23809 0.468809 0.0405158 -0.00494222 0.00793237 0.00388558 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00092 -0.000151798 0.0636998 3.99975 0.000116477 4.00095 +EDGE_SE3:QUAT 1464 1465 4.14569 -0.0654485 0.0212429 -0.000168478 -0.00210075 0.00449228 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.89013e-06 -0.0167967 3.99998 -3.77401e-05 3.99999 +EDGE_SE3:QUAT 1384 1464 3.43129 -0.0812878 0.0104045 0.00902996 -0.00187857 -0.109496 0.993944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 3.53718e-06 -0.00298771 4 -5.78482e-05 3.95204 +EDGE_SE3:QUAT 1385 1464 -0.792823 0.406429 0.00990173 0.00012062 0.00300925 0.00677899 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 2.92347e-06 0.0240633 3.99996 8.15835e-05 3.99996 +EDGE_SE3:QUAT 1386 1464 -5.01712 0.394402 -0.00757751 -0.000679233 0.00208979 0.0312614 0.999509 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -2.43354e-06 0.0169487 3.99998 0.000266059 3.99616 +EDGE_SE3:QUAT 1465 1466 4.29887 -0.0637197 0.0155035 -0.000486185 0.00283325 0.00236219 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -5.05943e-06 0.0226802 3.99997 2.67013e-05 4.00011 +EDGE_SE3:QUAT 1385 1465 3.35834 0.390558 0.00204623 0.00022986 0.000822166 0.0115337 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 9.36524e-07 0.00654422 4 3.768e-05 3.99948 +EDGE_SE3:QUAT 1386 1465 -0.870077 0.588001 0.000244507 -0.000409886 6.28726e-05 0.0355015 0.99937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.45091e-07 0.000676502 4 1.30359e-05 3.99496 +EDGE_SE3:QUAT 1387 1465 -4.96614 0.780007 -0.0316415 -0.000215348 -0.00255044 0.019881 0.999799 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 5.27743e-06 -0.0203405 3.99997 -0.000202032 3.99852 +EDGE_SE3:QUAT 1466 1467 4.02354 -0.155753 0.0110258 -0.000359939 -0.0019256 -0.0293576 0.999567 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 1.56188e-07 -0.0155118 3.99998 0.000228194 3.99661 +EDGE_SE3:QUAT 1386 1466 3.42929 0.830536 0.0150358 -0.000924628 0.00274341 0.0381007 0.99927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -3.30707e-06 0.0223224 3.99997 0.000427494 3.99432 +EDGE_SE3:QUAT 1387 1466 -0.639148 0.884406 0.00655828 -0.000690756 0.000159963 0.022313 0.999751 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.09753e-07 0.00146364 4 1.70128e-05 3.99801 +EDGE_SE3:QUAT 1388 1466 -4.676 1.01208 -0.0218591 -9.75695e-06 0.000275526 0.0131291 0.999914 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.31794e-08 0.00220517 4 1.44781e-05 3.99931 +EDGE_SE3:QUAT 1467 1468 4.27584 -0.339327 -0.0185309 -0.00321788 0.0114379 -0.0819032 0.996569 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00187 -0.000379321 0.0874691 3.99955 -0.00354033 3.97508 +EDGE_SE3:QUAT 1387 1467 3.40871 0.909236 0.00929212 -0.00116284 -0.00198201 -0.00733335 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 8.59959e-06 -0.0159573 3.99998 5.85253e-05 3.99985 +EDGE_SE3:QUAT 1388 1467 -0.635145 0.95988 -0.00693206 -8.27066e-05 -0.0019545 -0.0158534 0.999872 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -8.07921e-07 -0.0156461 3.99998 0.000124045 3.99906 +EDGE_SE3:QUAT 1389 1467 -4.90055 1.02835 -0.0748854 0.000126563 -0.0106126 -0.0127229 0.999863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0018 -3.97646e-05 -0.0848941 3.99955 0.000540946 4.00115 +EDGE_SE3:QUAT 1468 1469 4.08031 -0.685818 0.0012634 -0.00193414 0.00545399 -0.185884 0.982555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -0.000139368 0.0371774 3.99994 -0.00325189 3.86213 +EDGE_SE3:QUAT 1388 1468 3.61417 0.496346 -0.00774407 -0.00279489 0.00954295 -0.0979112 0.995145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00126 -0.00029506 0.0720042 3.9997 -0.00346215 3.96295 +EDGE_SE3:QUAT 1389 1468 -0.640783 0.590367 3.32495e-05 -0.00185985 0.000625102 -0.0946406 0.99551 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.34914e-06 0.00283417 4 -9.97391e-05 3.96417 +EDGE_SE3:QUAT 1390 1468 -4.81844 0.692284 -0.0457763 0.00288588 -0.00372728 -0.0980635 0.995169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -6.23454e-05 -0.0260154 3.99996 0.00121394 3.9617 +EDGE_SE3:QUAT 1469 1470 3.89518 -0.875517 0.000446126 -0.0024938 -0.000245116 -0.215815 0.976431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.9539e-06 -0.0080834 3.99999 0.00109917 3.81371 +EDGE_SE3:QUAT 109 1469 -2.29603 -6.62736 0.0412932 -0.00633769 0.00262594 0.605137 0.796092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 0.000293403 0.0453927 4.00002 0.016484 2.53575 +EDGE_SE3:QUAT 1389 1469 3.24833 -0.84924 0.0056109 -0.00333438 0.00612318 -0.278165 0.960508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 -0.000187616 0.0328554 3.99998 -0.00377903 3.69075 +EDGE_SE3:QUAT 1390 1469 -0.947926 -0.775083 -0.0244532 0.00216426 0.00265353 -0.281321 0.959608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.77066e-05 0.0256804 3.99997 -0.00382825 3.6836 +EDGE_SE3:QUAT 1391 1469 -5.18866 -0.630151 -0.0287087 -0.00191143 0.00215308 -0.288425 0.957498 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.83052e-05 0.00887174 4 -0.000852795 3.66726 +EDGE_SE3:QUAT 1470 1471 4.27517 -0.833613 0.00253522 0.00576428 0.000611783 -0.158333 0.987369 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 4.46219e-05 0.0154802 3.99998 -0.00150913 3.89978 +EDGE_SE3:QUAT 108 1470 5.02445 -2.15042 -0.0160686 -0.00650507 -7.3767e-05 0.609646 0.792647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 7.43929e-05 0.0355062 3.99993 0.0152853 2.51364 +EDGE_SE3:QUAT 109 1470 -0.399015 -3.1067 0.00756808 -0.00853372 -0.000313319 0.419023 0.907935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.93828e-05 0.036012 3.99987 0.0105412 3.29798 +EDGE_SE3:QUAT 110 1470 -5.27314 -2.47853 -0.0794223 -0.0110883 -0.00689228 0.320832 0.947046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99945 -2.29786e-05 -0.00707876 4.00001 0.00162489 3.58821 +EDGE_SE3:QUAT 1389 1470 6.06625 -3.68242 -0.0258038 -0.00706276 0.00569826 -0.47892 0.877812 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 8.07317e-05 -0.00354678 3.99998 0.00546937 3.08248 +EDGE_SE3:QUAT 1390 1470 1.86347 -3.59877 -0.0424186 -0.000574439 0.00350821 -0.481675 0.876343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -7.11145e-05 0.0160821 4.00002 -0.00268883 3.07201 +EDGE_SE3:QUAT 1391 1470 -2.42823 -3.50312 -0.0332404 -0.0045714 0.00225457 -0.488573 0.872508 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 4.64101e-05 -0.0105559 3.99997 0.00531434 3.04519 +EDGE_SE3:QUAT 1392 1470 -6.60036 -3.42167 -0.0861644 -0.00192375 0.00377505 -0.490751 0.871289 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.28892e-05 0.0104658 4.00002 -0.000611711 3.03666 +EDGE_SE3:QUAT 1471 1472 4.04856 -0.4236 -0.0227621 0.00603443 0.0109232 -0.0698172 0.997482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00196 6.53053e-05 0.0918261 3.99947 -0.00324241 3.98261 +EDGE_SE3:QUAT 108 1471 6.9198 1.76209 -0.0401665 -0.00227339 0.00257388 0.476044 0.879415 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 8.70619e-05 0.0250302 4 0.00630468 3.09369 +EDGE_SE3:QUAT 109 1471 3.00754 -0.393878 -0.00700376 -0.00330229 0.0014959 0.269555 0.962978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -1.93256e-06 0.0208516 3.99997 0.00322675 3.70947 +EDGE_SE3:QUAT 110 1471 -1.38361 -0.558293 -0.0251374 -0.00453622 -0.00601002 0.166702 0.985979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 0.0001751 -0.0371843 3.99994 -0.00279403 3.88918 +EDGE_SE3:QUAT 111 1471 -5.73554 -0.228541 -0.0836403 -0.00545028 -0.0119341 0.129516 0.991491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00167 0.00059275 -0.0847304 3.99962 -0.0052744 3.93469 +EDGE_SE3:QUAT 1472 1473 4.08355 -0.211975 0.0102326 -0.000846254 -2.30561e-05 -0.0268514 0.999639 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.3014e-07 -0.000456794 4 7.35212e-06 3.99712 +EDGE_SE3:QUAT 109 1472 6.67012 1.31941 -0.0411394 -0.000666321 0.013655 0.202226 0.979243 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00271 0.000824445 0.104242 3.99946 0.0103795 3.83913 +EDGE_SE3:QUAT 110 1472 2.56242 0.37191 0.00201844 0.000279255 0.00547048 0.097703 0.995201 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 7.40883e-05 0.0428176 3.99989 0.00207694 3.96227 +EDGE_SE3:QUAT 111 1472 -1.74248 0.41739 -0.00854583 -0.000104836 -0.000896606 0.0600687 0.998194 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.50046e-06 -0.0070587 4 -0.000210861 3.98558 +EDGE_SE3:QUAT 112 1472 -6.03424 0.542343 0.00975383 0.00527585 0.00122543 0.05104 0.998682 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 1.53828e-05 0.00653907 4 0.000139165 3.98959 +EDGE_SE3:QUAT 1473 1474 4.23839 -0.143759 0.00982269 -0.00429372 -0.00290335 -0.0133816 0.999897 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 4.89921e-05 -0.0239101 3.99996 0.000160605 3.99943 +EDGE_SE3:QUAT 110 1473 6.59781 0.946342 -0.0348838 -0.000955076 0.00531723 0.0707374 0.99748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 2.8358e-05 0.0430314 3.99989 0.00152754 3.98045 +EDGE_SE3:QUAT 111 1473 2.32587 0.682854 0.0078952 -0.000991146 -0.000925705 0.0333744 0.999442 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.02875e-06 -0.00699663 4 -0.000114497 3.99556 +EDGE_SE3:QUAT 112 1473 -1.96518 0.744387 0.0116552 0.00439033 0.0012195 0.0241126 0.999699 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.83677e-05 0.00847739 4 9.71931e-05 3.99769 +EDGE_SE3:QUAT 113 1473 -6.56345 0.820083 0.0212472 0.00412216 0.00279343 0.0244108 0.99969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 4.6881e-05 0.0211204 3.99997 0.000253515 3.99773 +EDGE_SE3:QUAT 1474 1475 3.98922 -0.10484 0.00900901 5.00975e-05 0.000583363 -0.00361272 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.74425e-08 0.00466899 4 -8.43476e-06 3.99995 +EDGE_SE3:QUAT 111 1474 6.54847 0.825137 0.0205086 -0.00511925 -0.00387087 0.0198343 0.999783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 8.17523e-05 -0.0297307 3.99995 -0.000292524 3.99865 +EDGE_SE3:QUAT 112 1474 2.2734 0.813765 0.00770636 0.000307909 -0.00166986 0.0108784 0.999939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.33323e-06 -0.0133968 3.99999 -7.29177e-05 3.99957 +EDGE_SE3:QUAT 113 1474 -2.35229 0.897666 0.00244581 0.000167863 3.81729e-05 0.010654 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.3557e-08 0.000283872 4 1.47399e-06 3.99955 +EDGE_SE3:QUAT 114 1474 -6.39054 0.990139 -0.00310044 0.00268583 3.32002e-05 0.00980574 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -2.0925e-07 -5.04561e-05 4 -7.63948e-07 3.99962 +EDGE_SE3:QUAT 1475 1476 4.03803 -0.113248 0.0139855 -0.00120185 -0.00111537 -0.00705802 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 5.22867e-06 -0.00902411 3.99999 3.1929e-05 3.99982 +EDGE_SE3:QUAT 112 1475 6.25136 0.781443 0.0270484 0.000254614 -0.00122135 0.00735653 0.999972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.83312e-07 -0.00979257 3.99999 -3.60377e-05 3.99981 +EDGE_SE3:QUAT 113 1475 1.63134 0.868596 0.0103566 0.000331621 0.000424355 0.00731224 0.999973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.87588e-07 0.00336547 4 1.22702e-05 3.99979 +EDGE_SE3:QUAT 114 1475 -2.40058 0.972219 0.0120254 0.00238561 0.000593029 0.00592371 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.43606e-06 0.00457437 4 1.34e-05 3.99986 +EDGE_SE3:QUAT 115 1475 -6.53388 1.06738 -0.00157368 0.00183038 0.00134722 0.00514496 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.94588e-06 0.0106643 3.99999 2.74153e-05 3.99992 +EDGE_SE3:QUAT 1476 1477 4.10552 -0.110055 0.0112503 -1.31279e-05 -0.00314302 -0.00339448 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -6.39761e-07 -0.0251451 3.99996 4.26787e-05 4.00011 +EDGE_SE3:QUAT 113 1476 5.68552 0.822915 0.0155433 -0.00105142 -0.000695087 6.63937e-06 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.92334e-06 -0.00556061 4 -3.06511e-08 4.00001 +EDGE_SE3:QUAT 114 1476 1.62254 0.90536 0.015738 0.00125794 -0.000524126 -0.00101751 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.63106e-06 -0.00417763 4 2.13103e-06 4 +EDGE_SE3:QUAT 115 1476 -2.49546 0.99158 -0.000391617 0.000598129 0.000275632 -0.0019348 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.61425e-07 0.00221893 4 -2.14997e-06 3.99999 +EDGE_SE3:QUAT 116 1476 -6.76573 1.08286 0.0571105 -0.00473279 0.00606688 7.36175e-05 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -0.000114855 0.0485439 3.99985 -2.39438e-06 4.00059 +EDGE_SE3:QUAT 1477 1478 4.02654 -0.111934 0.0194357 0.00553886 -0.00232018 0.000444295 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.14568e-05 -0.0185904 3.99998 -3.41483e-06 4.00009 +EDGE_SE3:QUAT 114 1477 5.71968 0.772597 0.0254069 0.0014303 -0.00365608 -0.00420483 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 -2.21952e-05 -0.0291769 3.99995 6.17566e-05 4.00014 +EDGE_SE3:QUAT 115 1477 1.61596 0.8619 0.00664708 0.000634681 -0.00299471 -0.00473411 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -8.60467e-06 -0.0239215 3.99996 5.67362e-05 4.00005 +EDGE_SE3:QUAT 116 1477 -2.66116 0.970357 0.014377 -0.00480596 0.00295175 -0.00299032 0.99998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -5.68129e-05 0.0234411 3.99997 -3.59585e-05 4.0001 +EDGE_SE3:QUAT 117 1477 -6.76974 1.03693 0.0264915 -0.00576659 0.00424056 -0.000607624 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -9.79324e-05 0.0338829 3.99993 -1.27755e-05 4.00029 +EDGE_SE3:QUAT 1478 1479 4.03734 -0.0796993 0.0145332 -0.000545831 0.00030761 0.0011231 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.71726e-07 0.00246823 4 1.38617e-06 4 +EDGE_SE3:QUAT 115 1478 5.65259 0.709876 0.0497949 0.00628113 -0.00542483 -0.00468639 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 -0.000138124 -0.0430457 3.99988 0.000104997 4.00038 +EDGE_SE3:QUAT 116 1478 1.378 0.84151 0.0142231 0.000604399 0.000410593 -0.00289004 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.89269e-07 0.00330566 4 -4.78437e-06 3.99997 +EDGE_SE3:QUAT 117 1478 -2.72152 0.923538 0.0122044 -0.000261814 0.00171486 -0.000256032 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -1.8139e-06 0.0137182 3.99999 -1.77465e-06 4.00005 +EDGE_SE3:QUAT 118 1478 -6.94701 0.954676 -0.223028 0.00099851 -0.0138284 0.00441437 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00306 -3.512e-05 -0.110751 3.99923 -0.000240386 4.00299 +EDGE_SE3:QUAT 1479 1480 4.06568 -0.0903932 -0.0125366 0.00131546 0.0105797 0.000214579 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00178 5.63296e-05 0.0846671 3.99955 1.26299e-05 4.00179 +EDGE_SE3:QUAT 116 1479 5.41217 0.732905 0.0196223 0.000132241 0.000893931 -0.00204403 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 4.33917e-07 0.00715467 4 -7.31079e-06 4 +EDGE_SE3:QUAT 117 1479 1.30967 0.839927 0.0144666 -0.000908623 0.00217524 0.000755711 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -7.82551e-06 0.0174104 3.99998 6.47673e-06 4.00007 +EDGE_SE3:QUAT 118 1479 -2.90738 0.911923 -0.093032 0.000315928 -0.0133341 0.00587811 0.999894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00285 8.21506e-06 -0.106756 3.99929 -0.000313015 4.00271 +EDGE_SE3:QUAT 119 1479 -6.92752 0.983903 -0.114179 -0.00137869 -0.0128601 0.00969437 0.999869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00263 0.000109332 -0.102765 3.99934 -0.000504162 4.00226 +EDGE_SE3:QUAT 1480 1481 4.4027 -0.0964018 0.00956873 0.00131782 0.00172848 0.0013604 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 9.19002e-06 0.0138064 3.99999 9.48073e-06 4.00004 +EDGE_SE3:QUAT 117 1480 5.39488 0.753522 -0.018133 0.000429637 0.0126717 0.00144506 0.999919 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00257 2.73962e-05 0.101423 3.99936 7.50592e-05 4.00256 +EDGE_SE3:QUAT 118 1480 1.15717 0.868126 0.00434 0.00155768 -0.00291079 0.00606353 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.70125e-05 -0.023399 3.99997 -7.07405e-05 3.99999 +EDGE_SE3:QUAT 119 1480 -2.86857 0.964335 -0.0178245 -0.000104424 -0.00241834 0.0101641 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.43407e-06 -0.0193314 3.99998 -9.82373e-05 3.99968 +EDGE_SE3:QUAT 120 1480 -7.41797 1.01564 -0.0194015 0.0019006 -0.00130274 0.0144954 0.999892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -9.69913e-06 -0.0107492 3.99999 -7.86175e-05 3.99919 +EDGE_SE3:QUAT 1481 1482 4.31334 -0.0932705 0.0232582 -0.00411496 0.00105554 -0.00483401 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -1.68417e-05 0.00820517 4 -1.97447e-05 3.99992 +EDGE_SE3:QUAT 118 1481 5.55834 0.823233 0.0392933 0.00305923 -0.00107209 0.00791477 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.348e-05 -0.00886638 3.99999 -3.53813e-05 3.99977 +EDGE_SE3:QUAT 119 1481 1.52979 0.975911 0.00889807 0.00127793 -0.000606259 0.0117956 0.999929 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.14213e-06 -0.00502992 4 -3.00071e-05 3.99945 +EDGE_SE3:QUAT 120 1481 -3.01235 1.05472 0.0041473 0.00311254 0.000569897 0.0160675 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 5.94725e-06 0.00395733 4 3.01997e-05 3.99897 +EDGE_SE3:QUAT 121 1481 -7.42442 1.20448 -0.0248087 0.0052876 0.000268605 0.0109442 0.999926 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 3.24232e-06 0.00145401 4 6.69411e-06 3.99952 +EDGE_SE3:QUAT 1482 1483 4.09741 -0.103433 0.0338465 -0.00141821 -0.00256226 -0.00441016 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 1.39082e-05 -0.020573 3.99997 4.51981e-05 4.00003 +EDGE_SE3:QUAT 119 1482 5.83517 0.975146 0.0336244 -0.00267956 0.000433572 0.00675298 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.00104e-06 0.00368544 4 1.26747e-05 3.99982 +EDGE_SE3:QUAT 120 1482 1.27703 1.10628 0.0148315 -0.000658852 0.0016412 0.0112221 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.63034e-06 0.013216 3.99999 7.4276e-05 3.99954 +EDGE_SE3:QUAT 121 1482 -3.14059 1.20302 -0.00572865 0.00130595 0.00158157 0.00642687 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 8.55475e-06 0.0125511 3.99999 4.0302e-05 3.99987 +EDGE_SE3:QUAT 1483 1484 4.13095 -0.104536 0.0237417 -0.000329009 -0.0043357 -0.00840089 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0003 1.91828e-06 -0.0347174 3.99992 0.00014575 4.00002 +EDGE_SE3:QUAT 120 1483 5.38226 1.08818 0.0376782 -0.00209554 -0.000769049 0.006676 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.30195e-06 -0.00598408 4 -1.98162e-05 3.99983 +EDGE_SE3:QUAT 121 1483 0.975118 1.16333 0.0128653 -0.000100675 -0.000878087 0.00174642 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 3.85766e-07 -0.00702257 4 -6.13348e-06 4 +EDGE_SE3:QUAT 122 1483 -3.39574 1.25276 -0.0214668 0.00163732 -0.00020467 -0.00434306 0.999989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.25126e-06 -0.00155198 4 3.30987e-06 3.99993 +EDGE_SE3:QUAT 123 1483 -7.41178 1.31477 0.0479328 -0.00425658 0.0087108 -0.000499579 0.999953 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00114 -0.000149302 0.0696774 3.9997 -2.5166e-05 4.00121 +EDGE_SE3:QUAT 1484 1485 4.03598 -0.150293 0.0355477 0.00350853 -0.00560621 -0.0186616 0.999804 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00044 -9.05056e-05 -0.0440445 3.99988 0.000411159 3.99909 +EDGE_SE3:QUAT 121 1484 5.09387 1.06967 0.042476 -0.000263889 -0.00519724 -0.00663275 0.999964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 1.18785e-06 -0.0416001 3.99989 0.00013785 4.00026 +EDGE_SE3:QUAT 122 1484 0.734815 1.11938 0.00137678 0.000962476 -0.00477088 -0.0127873 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 -2.52144e-05 -0.0380129 3.99991 0.000243287 3.99971 +EDGE_SE3:QUAT 123 1484 -3.2834 1.21114 0.000418874 -0.00453607 0.00437786 -0.00871492 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 -8.19281e-05 0.0345457 3.99993 -0.000151907 3.99999 +EDGE_SE3:QUAT 1485 1486 4.21347 -0.203525 0.0288791 -0.00146231 0.0146922 -0.0357368 0.999252 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0034 -0.000268726 0.116772 3.99916 -0.00209365 3.9983 +EDGE_SE3:QUAT 122 1485 4.75416 0.858864 0.078001 0.00463317 -0.0101859 -0.0311761 0.999451 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0015 -0.000258283 -0.0796604 3.99961 0.00124457 3.9977 +EDGE_SE3:QUAT 123 1485 0.741821 0.98501 0.00639703 -0.00122457 -0.00123516 -0.0274524 0.999622 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 5.30184e-06 -0.0102734 3.99999 0.000142764 3.99701 +EDGE_SE3:QUAT 124 1485 -3.61011 0.996507 -0.0987152 0.00122935 -0.00967736 -0.016318 0.999819 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00148 -8.39245e-05 -0.0771721 3.99963 0.000632275 4.00042 +EDGE_SE3:QUAT 1486 1487 4.02384 -0.331137 -0.00751945 -0.000367138 0.00407262 -0.087318 0.996172 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -3.94437e-05 0.0318281 3.99994 -0.00137891 3.96976 +EDGE_SE3:QUAT 123 1486 4.91505 0.547914 0.0409439 -0.00244236 0.0134428 -0.0634767 0.99789 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00274 -0.000393723 0.105099 3.99933 -0.00332551 3.98664 +EDGE_SE3:QUAT 124 1486 0.596606 0.667523 0.0156978 0.000467923 0.00480178 -0.0518831 0.998642 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -1.98781e-05 0.0385531 3.99991 -0.00100129 3.9896 +EDGE_SE3:QUAT 125 1486 -3.61581 0.378953 -0.0472641 -0.00250639 -0.00499973 0.0240361 0.999695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00036 6.28795e-05 -0.0392434 3.99991 -0.000470175 3.99807 +EDGE_SE3:QUAT 1487 1488 3.98277 -0.648366 0.0191666 -0.00221956 -0.00519966 -0.175096 0.984535 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -7.7112e-05 -0.0442721 3.99989 0.00395447 3.87785 +EDGE_SE3:QUAT 124 1487 4.57267 -0.0691251 -0.0302798 -0.000195596 0.00893177 -0.139014 0.99025 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -0.000261716 0.0690885 3.99973 -0.0047502 3.92389 +EDGE_SE3:QUAT 125 1487 0.417025 0.247002 -0.00623181 -0.00230674 -0.00131451 -0.0639349 0.997951 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.13793e-05 -0.0122166 3.99999 0.000408589 3.98369 +EDGE_SE3:QUAT 126 1487 -3.6943 -0.531294 0.00777728 0.00346814 0.0047579 0.13474 0.990863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 0.000106061 0.0314924 3.99995 0.00197396 3.92763 +EDGE_SE3:QUAT 1417 1487 0.234055 -7.46189 0.0489547 -0.00968527 0.00309274 0.613119 0.789925 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0007 0.000568516 0.0656158 4.00001 0.0248966 2.49741 +EDGE_SE3:QUAT 1488 1489 4.06592 -1.01414 -0.00537708 0.00487005 0.00146868 -0.242897 0.970039 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.61176e-05 0.0243622 3.99995 -0.00348771 3.76415 +EDGE_SE3:QUAT 80 1488 4.99954 4.98078 0.0548845 0.00130617 0.0110864 -0.883969 0.467413 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -6.09969e-05 0.0156917 4.0004 0.0182577 0.874152 +EDGE_SE3:QUAT 81 1488 1.02003 5.05662 0.0507628 0.000292663 0.0121416 -0.884659 0.46608 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 3.8766e-05 0.0113186 4.00026 0.023448 0.869221 +EDGE_SE3:QUAT 82 1488 -3.05076 5.17217 0.0395648 0.00211264 0.0119994 -0.888662 0.4584 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9997 -0.000124336 0.0199098 4.00058 0.0186126 0.840834 +EDGE_SE3:QUAT 125 1488 4.28189 -0.908184 0.0278668 -0.00471935 -0.0067687 -0.237699 0.971304 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00089 -0.000184092 -0.0625934 3.99979 0.00777982 3.77498 +EDGE_SE3:QUAT 126 1488 0.316957 -0.113296 -0.00530781 0.0012748 -0.000153006 -0.0410247 0.999157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.5289e-07 -0.000594084 4 7.87415e-06 3.99327 +EDGE_SE3:QUAT 127 1488 -3.65622 -1.03047 -0.0188502 -0.00260494 -0.00128689 0.233882 0.972261 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.05061e-06 -0.0024176 4 3.61075e-05 3.7812 +EDGE_SE3:QUAT 1416 1488 6.06782 -3.99467 0.036853 -0.00882167 -0.00608222 0.451705 0.892103 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99962 -0.000128782 0.00676364 3.99996 0.00634368 3.18378 +EDGE_SE3:QUAT 1417 1488 1.84665 -3.7717 0.0145315 -0.00873906 -0.00378328 0.465173 0.885169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 -0.000159733 0.020751 3.9999 0.00939886 3.13451 +EDGE_SE3:QUAT 1418 1488 -2.21202 -3.67723 -0.0210045 -0.00773327 -0.00366814 0.457723 0.889054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.000124035 0.01592 3.99993 0.00762261 3.16198 +EDGE_SE3:QUAT 1419 1488 -6.3991 -3.45582 -0.109244 -0.0100526 -0.00868964 0.446658 0.894606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99946 -7.72534e-05 -0.00306316 4 0.00502743 3.20185 +EDGE_SE3:QUAT 1489 1490 3.93908 -0.773746 0.00120265 0.00203929 0.00961181 -0.158404 0.987326 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0015 -0.000282853 0.0778561 3.99966 -0.00619238 3.90115 +EDGE_SE3:QUAT 79 1489 6.25438 1.69499 -0.0228371 -0.00425275 0.00872025 -0.980351 0.197021 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.0004e-05 -0.0174401 3.99972 0.0379841 0.155721 +EDGE_SE3:QUAT 80 1489 1.8887 2.20166 0.0229929 0.00227506 0.00739623 -0.971117 0.23848 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 6.12731e-05 0.0106454 4.00012 0.0213711 0.227647 +EDGE_SE3:QUAT 81 1489 -2.09351 2.29914 0.0237385 0.00121738 0.00810176 -0.971584 0.236553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 9.22273e-05 0.00611917 3.99997 0.0257893 0.22402 +EDGE_SE3:QUAT 82 1489 -6.22729 2.46258 -0.0054506 0.00316516 0.0084548 -0.973655 0.227846 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 7.36669e-05 0.0144074 4.00023 0.0240435 0.207868 +EDGE_SE3:QUAT 126 1489 4.27826 -1.44229 -0.0107664 0.00600775 0.00131734 -0.282766 0.959169 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 3.75785e-05 0.0285997 3.99993 -0.00493673 3.68037 +EDGE_SE3:QUAT 127 1489 0.420603 -0.0960996 -0.00726595 0.00228937 0.00049578 -0.00923947 0.999955 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.86663e-06 0.00421952 4 -1.98683e-05 3.99966 +EDGE_SE3:QUAT 128 1489 -3.53593 -0.526356 -0.0624636 -0.00199696 -0.00766445 0.184773 0.982749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00071 0.000268363 -0.0538827 3.99986 -0.00474763 3.86416 +EDGE_SE3:QUAT 129 1489 -7.39602 -0.90862 -0.108151 -0.00320038 -0.011195 0.232055 0.972633 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00131 0.000642521 -0.0738484 3.9998 -0.0079499 3.78595 +EDGE_SE3:QUAT 1417 1489 4.99033 -1.0021 0.0337388 -0.00353745 -0.00228266 0.235798 0.971793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.38555e-05 -0.0071208 4 -0.000384541 3.77761 +EDGE_SE3:QUAT 1418 1489 0.97466 -0.948536 0.00197829 -0.00273564 -0.00202248 0.227924 0.973673 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.44429e-05 -0.00771227 4 -0.000545397 3.79221 +EDGE_SE3:QUAT 1419 1489 -3.18941 -0.834577 -0.0506106 -0.00327076 -0.00698342 0.215725 0.976424 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00043 0.00024313 -0.0438114 3.99993 -0.00428095 3.81432 +EDGE_SE3:QUAT 1420 1489 -7.44894 -0.705599 -0.122738 -0.00265882 -0.0120327 0.211198 0.977366 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0017 0.000706279 -0.083382 3.9997 -0.00835313 3.82331 +EDGE_SE3:QUAT 1490 1491 4.07239 -0.307765 -0.0079528 0.000712247 0.00213967 -0.0422176 0.999106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.46906e-06 0.0174323 3.99998 -0.000370128 3.99295 +EDGE_SE3:QUAT 78 1490 6.53294 -1.38136 -0.0304694 0.00164335 -0.0111133 0.982077 0.188145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000178471 -0.00750673 3.99983 0.0381835 0.141991 +EDGE_SE3:QUAT 79 1490 2.35035 0.890269 0.0115657 0.00434196 0.00755774 -0.999191 0.039249 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 0.000128162 0.0174126 4.00014 0.028756 0.00644491 +EDGE_SE3:QUAT 80 1490 -1.94564 1.08787 0.00396792 0.0110442 0.00779215 -0.996592 0.0813787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99942 0.000111527 0.0446442 4.00202 0.023527 0.0271315 +EDGE_SE3:QUAT 81 1490 -5.94151 1.19977 0.008822 0.0100778 0.00860461 -0.996731 0.0796981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000166156 0.040727 4.00164 0.0275043 0.0260154 +EDGE_SE3:QUAT 127 1490 4.33619 -0.927052 -0.0129671 0.00445882 0.0104565 -0.167574 0.985794 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0019 -0.000288856 0.0889897 3.99954 -0.00760244 3.88965 +EDGE_SE3:QUAT 128 1490 0.411831 0.172929 0.00491498 -0.000364525 0.00171466 0.0266465 0.999643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 -6.22306e-07 0.0138193 3.99999 0.000184551 3.99721 +EDGE_SE3:QUAT 129 1490 -3.55878 0.178769 -0.0103691 -0.00127661 -0.00166779 0.074861 0.997192 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.17521e-05 -0.0120878 3.99999 -0.000436825 3.97762 +EDGE_SE3:QUAT 1418 1490 4.82655 0.101998 0.01902 -0.00235546 0.00760738 0.0707846 0.99746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 2.83518e-05 0.0624094 3.99976 0.00222497 3.98093 +EDGE_SE3:QUAT 1419 1490 0.695318 0.126605 0.0125753 -0.00189815 0.00233387 0.0584272 0.998287 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -1.08248e-05 0.0199036 3.99997 0.000593244 3.98644 +EDGE_SE3:QUAT 1420 1490 -3.56541 0.213478 -0.0185383 -0.000563225 -0.00237946 0.0538487 0.998546 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 1.22567e-05 -0.01859 3.99998 -0.000496616 3.98849 +EDGE_SE3:QUAT 1491 1492 4.02859 -0.1208 0.00218551 -0.00178257 0.00101924 -0.0105922 0.999942 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.24943e-06 0.00792602 4 -4.16174e-05 3.99957 +EDGE_SE3:QUAT 77 1491 6.56049 -2.85055 -0.000208783 -0.00288612 -0.01119 0.843169 0.537524 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000169065 0.0014558 3.99993 0.0247569 1.15604 +EDGE_SE3:QUAT 78 1491 2.88545 0.408196 -0.0032323 4.31068e-05 -0.00998158 0.973236 0.229591 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000140894 -0.00115302 3.99976 0.0346876 0.21117 +EDGE_SE3:QUAT 79 1491 -1.7121 0.885059 -0.0299064 -0.00640067 -0.00736551 0.999948 0.00285908 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000190209 0.0256046 4.00043 0.0296137 0.000415806 +EDGE_SE3:QUAT 80 1491 -5.99229 0.723332 -0.0928046 0.0135291 0.00768395 -0.9991 0.0394601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99921 0.000252098 0.0542431 4.00288 0.0263781 0.0071394 +EDGE_SE3:QUAT 128 1491 4.5006 0.086664 -0.0130321 -8.34068e-05 0.00406653 -0.0152605 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -7.4056e-06 0.0325075 3.99993 -0.000248048 3.99933 +EDGE_SE3:QUAT 129 1491 0.503075 0.482777 8.14354e-05 -0.000836082 0.000420553 0.0330965 0.999452 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.42581e-06 0.00369071 4 6.28719e-05 3.99562 +EDGE_SE3:QUAT 130 1491 -3.80548 0.600509 0.00140561 0.000872126 -2.67578e-05 0.0224583 0.999747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.2855e-07 -0.000448859 4 -5.91941e-06 3.99798 +EDGE_SE3:QUAT 192 1491 1.98818 -7.22795 0.0709099 5.71047e-05 0.00763798 0.893892 0.448217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -3.94517e-05 0.00521577 4.00006 -0.0165016 0.803716 +EDGE_SE3:QUAT 833 1491 2.55427 7.02366 0.0503742 0.00359175 0.00113939 -0.703598 0.710588 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -0.00010498 0.0235888 4.00004 -0.0101403 2.01993 +EDGE_SE3:QUAT 834 1491 -1.49048 7.09511 0.0809045 0.00248442 0.00729741 -0.706568 0.707603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -0.000455839 0.0347399 4.00036 -0.00705648 2.00324 +EDGE_SE3:QUAT 1419 1491 4.76308 0.282038 -0.0103065 -0.00142638 0.00456744 0.0160938 0.999859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -1.81661e-05 0.0368034 3.99992 0.000296197 3.9993 +EDGE_SE3:QUAT 1420 1491 0.515373 0.343885 0.00689747 0.000269949 -0.00023752 0.011593 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.46984e-07 -0.00193733 4 -1.13012e-05 3.99946 +EDGE_SE3:QUAT 1421 1491 -3.81937 0.403079 -0.0112902 0.00177392 -0.0010868 0.0170443 0.999853 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.62144e-06 -0.00905336 3.99999 -7.81215e-05 3.99886 +EDGE_SE3:QUAT 1492 1493 4.12519 -0.123897 0.0238913 0.00208821 -0.000926097 -0.00574189 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.64938e-06 -0.00726451 4 2.07598e-05 3.99988 +EDGE_SE3:QUAT 77 1492 4.97128 0.841791 0.0376854 -0.00462283 -0.0118938 0.837506 0.54628 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99971 -0.000275209 0.00921745 3.99975 0.0302362 1.19413 +EDGE_SE3:QUAT 78 1492 -0.666767 2.31313 0.0269573 -0.00119321 -0.0114886 0.970742 0.239847 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000174678 0.00389687 3.99958 0.041636 0.230574 +EDGE_SE3:QUAT 79 1492 -5.7319 1.03421 -0.0744527 -0.00728666 -0.00888294 0.999845 0.0133157 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000266879 0.0291572 4.00049 0.0363009 0.00125123 +EDGE_SE3:QUAT 129 1492 4.50772 0.623721 -0.0020048 -0.00250948 0.00145846 0.0226142 0.99974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.45038e-05 0.0123395 3.99999 0.000141919 3.99799 +EDGE_SE3:QUAT 130 1492 0.221781 0.667168 0.00163342 -0.000978301 0.00119689 0.012203 0.999924 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.34652e-06 0.00971623 3.99999 5.95371e-05 3.99943 +EDGE_SE3:QUAT 131 1492 -3.95216 0.822079 -0.0188517 -0.00102175 0.000367264 -0.00181324 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.49166e-06 0.00291587 4 -2.64014e-06 3.99999 +EDGE_SE3:QUAT 191 1492 5.37047 -3.0382 0.00414038 -0.00322849 -0.00305498 0.967059 0.254514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.38492e-05 0.0137041 4.00001 0.0164345 0.259229 +EDGE_SE3:QUAT 192 1492 -0.323931 -3.92731 0.0475663 -0.00162175 0.00667832 0.889162 0.457541 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 6.63005e-05 0.0132998 4.00023 -0.00911483 0.837479 +EDGE_SE3:QUAT 193 1492 -5.73697 -2.72328 0.224162 0.00761426 0.0171654 0.790001 0.612818 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99925 -0.000529135 -0.0105292 3.99966 -0.0368049 1.50308 +EDGE_SE3:QUAT 832 1492 6.66581 2.95615 0.137012 0.0135943 -0.0066984 -0.706772 0.707279 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 0.00017501 0.057938 3.99945 -0.0384125 2.00264 +EDGE_SE3:QUAT 833 1492 2.46972 3.01366 0.0224166 0.00319605 0.00304493 -0.710751 0.70343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 -0.000194793 0.026559 4.00012 -0.00899765 1.97949 +EDGE_SE3:QUAT 834 1492 -1.61348 3.06646 0.0241228 0.00204315 0.00927489 -0.714044 0.700036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -0.000575059 0.0370122 4.0005 -0.00531586 1.96073 +EDGE_SE3:QUAT 835 1492 -5.70374 3.18007 0.190518 -0.00747278 0.0217067 -0.715718 0.698012 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9989 -7.79173e-05 0.0168047 4.00053 0.0229632 1.95011 +EDGE_SE3:QUAT 1420 1492 4.55327 0.315411 0.0111973 -0.00150486 0.000696542 0.000902828 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.1986e-06 0.00558863 4 2.50764e-06 4 +EDGE_SE3:QUAT 1421 1492 0.197176 0.431931 0.00214044 1.92908e-07 -9.15837e-05 0.0065859 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.25509e-09 -0.000732637 4 -2.4125e-06 3.99983 +EDGE_SE3:QUAT 1422 1492 -3.94737 0.542006 -0.00629532 -0.0013261 0.000902456 0.00665475 0.999977 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -4.74718e-06 0.00732506 4 2.44638e-05 3.99984 +EDGE_SE3:QUAT 1493 1494 4.241 -0.0954762 0.0116421 -0.00264687 0.000477283 -0.00364632 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.86767e-06 0.00370234 4 -6.6933e-06 3.99995 +EDGE_SE3:QUAT 77 1493 3.43519 4.6448 0.0837812 -0.00281175 -0.0106043 0.834592 0.550759 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 -0.000143829 0.000908671 3.99995 0.0225554 1.21361 +EDGE_SE3:QUAT 78 1493 -4.2418 4.33851 0.0636027 0.000349473 -0.00969828 0.969484 0.244961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.0001365 -0.00265937 3.99983 0.0324538 0.240312 +EDGE_SE3:QUAT 130 1493 4.35242 0.645345 0.0156322 0.00113349 0.000467299 0.00651593 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.08446e-06 0.00364952 4 1.17992e-05 3.99983 +EDGE_SE3:QUAT 131 1493 0.185235 0.679328 0.00364995 0.000869993 -0.000446335 -0.00763344 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.54207e-06 -0.00349067 4 1.32252e-05 3.99977 +EDGE_SE3:QUAT 132 1493 -4.10368 0.721353 0.00755554 0.0063947 0.00110141 -0.00532717 0.999965 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 2.97455e-05 0.00921916 3.99999 -2.47186e-05 3.99991 +EDGE_SE3:QUAT 190 1493 6.0279 0.432449 0.0268929 -0.0036169 -0.00717671 0.997838 0.0652346 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 9.07459e-05 0.0145448 3.99993 0.0302821 0.0173055 +EDGE_SE3:QUAT 191 1493 1.82494 -0.893964 0.00588922 -0.00192432 -0.00122088 0.965759 0.259431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.80441e-05 0.0082639 4.00002 0.00780656 0.269252 +EDGE_SE3:QUAT 192 1493 -2.60867 -0.501103 0.0312046 -3.40044e-05 0.00800088 0.886688 0.462299 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -2.86329e-05 0.00649591 4.00009 -0.0161498 0.855012 +EDGE_SE3:QUAT 193 1493 -6.62918 1.30054 0.204953 0.00952332 0.018356 0.786564 0.617163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99912 -0.000733374 -0.0182664 3.9994 -0.0428548 1.52475 +EDGE_SE3:QUAT 832 1493 6.53372 -1.17292 0.112245 0.0142287 -0.00860441 -0.710748 0.70325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000352301 0.0565353 3.99931 -0.040702 1.98 +EDGE_SE3:QUAT 833 1493 2.29107 -1.13591 0.00242161 0.00423815 0.00100515 -0.714776 0.69934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -0.00012992 0.0267221 4.00004 -0.0120524 1.95656 +EDGE_SE3:QUAT 834 1493 -1.8277 -1.05415 -0.0172785 0.00286976 0.00698526 -0.717899 0.696106 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 -0.000458298 0.0350798 4.00037 -0.00762341 1.93869 +EDGE_SE3:QUAT 835 1493 -5.94555 -0.940668 0.137786 -0.00718227 0.0197796 -0.719916 0.693742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99904 3.30476e-05 0.0122335 4.00036 0.0227933 1.92613 +EDGE_SE3:QUAT 1421 1493 4.33626 0.348763 0.0276686 0.00218396 -0.000956003 0.00101156 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.36779e-06 -0.0076745 4 -3.83795e-06 4.00001 +EDGE_SE3:QUAT 1422 1493 0.173208 0.469508 0.0105557 0.000754463 -7.01007e-06 0.00103807 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.58807e-08 -6.54786e-05 4 -3.56102e-08 4 +EDGE_SE3:QUAT 1423 1493 -4.21514 0.551954 0.0093859 0.00528617 0.000874141 -0.00068318 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 1.86226e-05 0.00703618 4 -2.31053e-06 4.00001 +EDGE_SE3:QUAT 1494 1495 4.00729 -0.0959893 0.0213248 -0.000898943 -0.00979188 -0.00153628 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00153 3.17284e-05 -0.0783775 3.99962 5.81996e-05 4.00153 +EDGE_SE3:QUAT 131 1494 4.39923 0.512071 0.0149197 -0.00195254 7.26568e-05 -0.0113496 0.999934 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.21772e-07 0.000315236 4 -1.28576e-06 3.99948 +EDGE_SE3:QUAT 132 1494 0.130405 0.576996 0.00297891 0.00345342 0.00153135 -0.00928818 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.14878e-05 0.012634 3.99999 -5.90639e-05 3.99969 +EDGE_SE3:QUAT 133 1494 -4.18905 0.641357 0.0525788 0.00544473 0.00886422 -0.00303703 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00115 0.000188218 0.0711277 3.99968 -9.78807e-05 4.00123 +EDGE_SE3:QUAT 189 1494 5.69801 1.3262 0.0755627 -0.0114525 -0.0170839 0.999768 0.00646027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 0.000788274 0.0458306 4.00087 0.0689588 0.00188045 +EDGE_SE3:QUAT 190 1494 1.83832 1.08783 0.0135953 -0.00446117 -0.00991587 0.997567 0.0688643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 0.000143164 0.0179478 3.99979 0.0416408 0.0194854 +EDGE_SE3:QUAT 191 1494 -1.7893 1.31497 -0.00228016 -0.00329443 -0.0036078 0.964702 0.263297 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.9395e-05 0.0139489 3.99998 0.0184501 0.277442 +EDGE_SE3:QUAT 192 1494 -4.94756 3.01734 0.00415253 -0.00202794 0.00553533 0.884886 0.46577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.26907e-05 0.0147666 4.00023 -0.00517468 0.867858 +EDGE_SE3:QUAT 833 1494 2.09991 -5.34985 -0.0138419 0.00253157 0.00337005 -0.717306 0.696746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -0.000172154 0.0234362 4.00012 -0.00698058 1.942 +EDGE_SE3:QUAT 834 1494 -2.05918 -5.29172 -0.0674517 0.00126175 0.00948646 -0.720503 0.693386 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -0.000482317 0.0324341 4.00046 -0.00258964 1.92357 +EDGE_SE3:QUAT 1422 1494 4.44013 0.371847 0.0177588 -0.002112 0.000431726 -0.00222686 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.5774e-06 0.00339733 4 -3.77094e-06 3.99998 +EDGE_SE3:QUAT 1423 1494 0.0275314 0.436678 0.00925289 0.00224706 0.00153061 -0.00419414 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.36875e-05 0.0123576 3.99999 -2.58661e-05 3.99997 +EDGE_SE3:QUAT 1424 1494 -4.11036 0.535999 0.0647838 0.00443892 0.00946254 -0.00534917 0.999931 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00136 0.000157487 0.0760038 3.99964 -0.000194121 4.00133 +EDGE_SE3:QUAT 1495 1496 4.0831 -0.0581263 0.0016807 -0.000281089 0.00259027 0.00732679 0.99997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.73505e-06 0.0207457 3.99997 7.59877e-05 3.99989 +EDGE_SE3:QUAT 132 1495 4.13308 0.39909 0.0117851 0.00234351 -0.00832401 -0.0101127 0.999911 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00108 -9.43508e-05 -0.0663128 3.99973 0.000338919 4.00069 +EDGE_SE3:QUAT 133 1495 -0.189941 0.512646 0.0011715 0.00437373 -0.00101278 -0.00421411 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.7172e-05 -0.00788069 4 1.65527e-05 3.99994 +EDGE_SE3:QUAT 134 1495 -4.3808 0.643677 -0.0190173 0.00305958 -0.00306646 -0.00797721 0.999959 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -3.86971e-05 -0.0242369 3.99996 9.69655e-05 3.99989 +EDGE_SE3:QUAT 188 1495 5.71688 1.40712 0.0311547 -0.00256785 -0.0141341 0.999881 0.00558051 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000137025 0.0102748 3.9993 0.056643 0.000953226 +EDGE_SE3:QUAT 189 1495 1.69537 1.46372 0.010055 -0.00153107 -0.0181552 0.999804 0.0076947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.11626e-05 0.00612743 3.99871 0.0726928 0.00156778 +EDGE_SE3:QUAT 190 1495 -2.09934 1.73208 0.00594025 0.00546758 -0.0117181 0.99746 0.070049 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -0.00026181 -0.022066 4.00016 0.0432564 0.0202202 +EDGE_SE3:QUAT 191 1495 -5.14466 3.40419 0.0116558 0.00610037 -0.00714866 0.964373 0.264379 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99975 0.000138337 -0.0278776 4.00086 0.0117237 0.279839 +EDGE_SE3:QUAT 1423 1495 4.04964 0.31632 0.0172102 0.00137619 -0.00848274 -0.00538547 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00114 -5.5942e-05 -0.0677869 3.99971 0.00018496 4.00103 +EDGE_SE3:QUAT 1424 1495 -0.100754 0.399739 0.00519836 0.00332883 -0.00046976 -0.00686377 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -5.67818e-06 -0.00348358 4 1.16569e-05 3.99981 +EDGE_SE3:QUAT 1425 1495 -4.10412 0.493105 -0.0206866 0.00230955 -0.00322105 -0.00919291 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00014 -3.1617e-05 -0.0255111 3.99996 0.000117444 3.99982 +EDGE_SE3:QUAT 1496 1497 4.40103 -0.0555714 0.022109 0.00231375 -0.000332683 0.00891022 0.999958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -3.43284e-06 -0.00290851 4 -1.33175e-05 3.99968 +EDGE_SE3:QUAT 133 1496 3.90391 0.423963 0.00111186 0.0038863 0.00157062 0.003255 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.42111e-05 0.0124128 3.99999 2.03455e-05 4 +EDGE_SE3:QUAT 134 1496 -0.300315 0.513846 0.000556229 0.0026283 -0.000412585 -0.000343334 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.31996e-06 -0.00328982 4 5.74816e-07 4 +EDGE_SE3:QUAT 135 1496 -4.31796 0.654329 -0.0243364 -4.42661e-05 0.000214072 -0.0103341 0.999947 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.90417e-08 0.00170682 4 -8.80929e-06 3.99957 +EDGE_SE3:QUAT 187 1496 5.68595 1.42132 0.0323199 0.0060803 0.0119319 -0.99991 0.0012739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.00029058 0.024326 4.00003 0.0476718 0.000722542 +EDGE_SE3:QUAT 188 1496 1.65874 1.49545 0.0189373 0.00554981 0.0143029 -0.99988 0.00200582 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000319303 0.0222058 3.99968 0.057126 0.000955234 +EDGE_SE3:QUAT 189 1496 -2.38845 1.58616 0.00470413 -0.00439163 -0.018427 0.999821 0.000165422 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000323193 0.0175753 3.99895 0.0737093 0.0014359 +EDGE_SE3:QUAT 190 1496 -6.10375 2.35669 0.0594105 0.00263385 -0.0118558 0.997964 0.06262 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000175916 -0.010623 3.99966 0.0456447 0.0162365 +EDGE_SE3:QUAT 1424 1496 3.98337 0.284185 0.0053487 0.00322828 0.00227714 0.00107132 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 2.945e-05 0.0181756 3.99998 1.01293e-05 4.00008 +EDGE_SE3:QUAT 1425 1496 -0.0138146 0.361661 0.000573704 0.0020922 -0.000535936 -0.00145506 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.44406e-06 -0.00425092 4 3.09805e-06 4 +EDGE_SE3:QUAT 1426 1496 -4.2274 0.461322 -0.0183708 -0.00018641 -0.000205093 -0.00484383 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.49325e-07 -0.00165153 4 4.00837e-06 3.99991 +EDGE_SE3:QUAT 1497 1498 4.02738 -0.064159 0.025054 -0.00230579 -0.00046095 6.48628e-05 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.24895e-06 -0.00368578 4 -1.31265e-07 4 +EDGE_SE3:QUAT 134 1497 4.09067 0.454694 0.0243336 0.0049558 -0.000845101 0.00878712 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -1.83066e-05 -0.00728233 4 -3.2664e-05 3.9997 +EDGE_SE3:QUAT 135 1497 0.0743722 0.512221 -9.46378e-05 0.00223543 -0.000141209 -0.00124203 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.21355e-06 -0.00109634 4 6.74968e-07 3.99999 +EDGE_SE3:QUAT 136 1497 -4.04166 0.586288 -0.042081 0.00323786 -0.00124672 -0.0057238 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.58719e-05 -0.00975077 3.99999 2.781e-05 3.99989 +EDGE_SE3:QUAT 186 1497 5.35664 1.3848 0.0277728 0.00518873 0.00903344 -0.999882 0.011323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000187222 0.0207612 4.00013 0.0356563 0.000938468 +EDGE_SE3:QUAT 187 1497 1.26336 1.45943 0.00288792 0.006057 0.00961655 -0.99988 0.0104843 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000231187 0.0242348 4.00025 0.0379539 0.00094665 +EDGE_SE3:QUAT 188 1497 -2.73715 1.55182 -0.0146542 0.0052733 0.0124442 -0.99985 0.0108271 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.000268208 0.0211016 3.99986 0.0493096 0.00118816 +EDGE_SE3:QUAT 189 1497 -6.74427 1.64935 -0.0102497 0.00411178 0.0163792 -0.999815 0.00921954 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000284991 0.0164559 3.99923 0.0651975 0.00147064 +EDGE_SE3:QUAT 1425 1497 4.37662 0.286534 0.0309856 0.00423939 -0.000941599 0.00762653 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -1.6886e-05 -0.00791992 4 -3.05955e-05 3.99978 +EDGE_SE3:QUAT 1426 1497 0.184977 0.370131 0.0035725 0.00187638 -0.000601533 0.00407313 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -4.59296e-06 -0.00490384 4 -1.00324e-05 3.99994 +EDGE_SE3:QUAT 1427 1497 -3.87629 0.472742 -0.0246229 0.00266981 -2.40699e-05 0.000901512 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.08436e-07 -0.000221439 4 -1.04108e-07 4 +EDGE_SE3:QUAT 1498 1499 4.1288 -0.248248 0.0199238 -0.00146533 0.00924392 -0.0665768 0.997737 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0013 -0.000184776 0.0723131 3.99968 -0.00239374 3.98358 +EDGE_SE3:QUAT 135 1498 4.10468 0.445928 0.0242961 4.7719e-05 -0.000536083 -0.000888364 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.08435e-07 -0.00428815 4 1.90498e-06 4 +EDGE_SE3:QUAT 136 1498 -0.00941537 0.484539 -0.00320875 0.00100469 -0.00163094 -0.00535022 0.999984 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -6.84994e-06 -0.0129826 3.99999 3.47364e-05 3.99993 +EDGE_SE3:QUAT 137 1498 -4.1637 0.252044 -0.114964 0.000968598 -0.00976143 0.047047 0.998845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00153 7.03199e-05 -0.0784047 3.99962 -0.00184623 3.99268 +EDGE_SE3:QUAT 185 1498 5.78577 1.23609 -0.0236863 -0.000980711 0.0100255 -0.999904 0.00954182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.18149e-05 -0.00392383 3.99961 0.0401659 0.000771436 +EDGE_SE3:QUAT 186 1498 1.34173 1.33713 0.0126717 0.0050149 0.0113765 -0.999861 0.0111334 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000232586 0.020067 3.99992 0.0450488 0.0011039 +EDGE_SE3:QUAT 187 1498 -2.7501 1.44037 -0.0173459 0.00569649 0.0121894 -0.999856 0.0103158 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 0.000281553 0.0227943 3.99996 0.0482801 0.00113835 +EDGE_SE3:QUAT 188 1498 -6.73489 1.5085 -0.0337783 0.00501277 0.014846 -0.999813 0.0113113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.00031017 0.0200615 3.99956 0.0589139 0.00148029 +EDGE_SE3:QUAT 1426 1498 4.20698 0.354294 0.0354973 -0.000198942 -0.00110094 0.00405386 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.92509e-07 -0.00879762 4 -1.78315e-05 3.99995 +EDGE_SE3:QUAT 1427 1498 0.15632 0.419988 0.00447366 0.000310088 -0.000482458 0.00133131 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.9199e-07 -0.00386461 4 -2.57186e-06 4 +EDGE_SE3:QUAT 1428 1498 -4.13262 0.52866 -0.0922625 -0.000921668 -0.0084342 -0.0011512 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00114 2.91662e-05 -0.0675029 3.99972 3.73115e-05 4.00113 +EDGE_SE3:QUAT 1499 1500 4.00639 -0.637249 0.00246013 -0.00179289 0.00284035 -0.165771 0.986159 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -3.84126e-05 0.0182916 3.99999 -0.00139155 3.89016 +EDGE_SE3:QUAT 136 1499 4.10677 0.203169 0.0242606 -0.000439895 0.00779886 -0.0716706 0.997398 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00095 -0.000116169 0.0615464 3.99977 -0.00219727 3.9804 +EDGE_SE3:QUAT 137 1499 -0.0314903 0.380328 -0.00595024 -0.000128495 -0.000394283 -0.0194495 0.999811 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.31477e-07 -0.00318246 4 3.10396e-05 3.99849 +EDGE_SE3:QUAT 138 1499 -4.30161 -0.463578 -0.0461214 0.00296714 -0.00397541 0.157837 0.987453 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 1.84175e-05 -0.0361512 3.99992 -0.0029681 3.90068 +EDGE_SE3:QUAT 184 1499 6.01014 1.28081 -0.00542452 -5.38314e-06 -0.0128226 0.998135 0.0596807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -7.69789e-05 -1.13148e-06 3.99936 0.050833 0.0148956 +EDGE_SE3:QUAT 185 1499 1.67136 1.40085 0.0152248 -0.00784047 -0.011502 0.998262 0.0572589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000366245 0.0315053 4.00021 0.0492209 0.0139706 +EDGE_SE3:QUAT 186 1499 -2.78416 1.49919 4.88811e-05 -0.0136408 -0.0135483 0.998272 0.0555236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99943 0.000870369 0.0548136 4.00174 0.0598643 0.0139825 +EDGE_SE3:QUAT 187 1499 -6.83827 1.5894 -0.0366885 -0.0145076 -0.0143498 0.998246 0.0555689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99935 0.000982254 0.0582996 4.00198 0.0634434 0.0142119 +EDGE_SE3:QUAT 1427 1499 4.28709 0.191749 0.0262157 -0.000860153 0.00876146 -0.0651179 0.997839 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00119 -0.00014684 0.0689938 3.99971 -0.00223755 3.98423 +EDGE_SE3:QUAT 1428 1499 -0.000272614 0.271957 -0.000603081 -0.0020405 0.00066508 -0.0675039 0.997717 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -3.54255e-06 0.00363641 4 -0.000103742 3.98178 +EDGE_SE3:QUAT 1429 1499 -4.04715 0.371012 -0.0247757 -0.00239921 -0.000761787 -0.0691023 0.997606 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.91478e-06 -0.00803383 4 0.000299936 3.98092 +EDGE_SE3:QUAT 1500 1501 4.09104 -0.806633 -0.00943177 0.00141559 0.00199853 -0.183735 0.982973 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00008 -8.61852e-06 0.0182367 3.99998 -0.00174537 3.86505 +EDGE_SE3:QUAT 137 1500 3.93593 -0.393363 -0.000872656 -0.00183874 0.00255105 -0.184683 0.982793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -3.16939e-05 0.0153909 3.99999 -0.00126315 3.86363 +EDGE_SE3:QUAT 138 1500 -0.29297 0.178736 -0.00851143 0.00132126 -0.000814915 -0.00814913 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.3184e-06 -0.00638947 4 2.58785e-05 3.99974 +EDGE_SE3:QUAT 139 1500 -4.28343 -0.780174 -0.00693531 0.000743913 -0.00155702 0.203441 0.979086 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 8.5219e-06 -0.013457 3.99999 -0.00140333 3.83449 +EDGE_SE3:QUAT 183 1500 6.193 2.3242 0.0315692 0.000342827 -0.0168659 0.975028 0.22144 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.00040035 -0.00293891 3.99934 0.0587576 0.197064 +EDGE_SE3:QUAT 184 1500 2.11337 2.38614 0.0195871 -0.000899124 -0.0143037 0.974401 0.224359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000269753 0.00256215 3.99938 0.0516721 0.202059 +EDGE_SE3:QUAT 185 1500 -2.23741 2.47751 -0.0241423 -0.00927214 -0.0143369 0.974978 0.221643 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 0.000265265 0.0384821 3.99938 0.0660585 0.198021 +EDGE_SE3:QUAT 186 1500 -6.67657 2.55999 -0.0782634 -0.0148254 -0.0172616 0.975287 0.219765 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 0.000916362 0.0620157 3.9998 0.0856805 0.196083 +EDGE_SE3:QUAT 1428 1500 3.8705 -0.897843 -0.00380418 -0.00366675 0.00348174 -0.232133 0.972671 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.13314e-05 0.0157854 4 -0.0013475 3.78451 +EDGE_SE3:QUAT 1429 1500 -0.163772 -0.813688 -0.00739433 -0.00396111 0.0019846 -0.233369 0.972378 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -3.14952e-06 0.00390728 4 2.73535e-05 3.78215 +EDGE_SE3:QUAT 1430 1500 -4.20377 -0.709716 -0.012178 -0.00345911 0.00216169 -0.235105 0.971961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -1.16204e-05 0.00647995 4 -0.000321501 3.77891 +EDGE_SE3:QUAT 1501 1502 4.05631 -0.799304 0.0060267 0.00298764 -0.00445072 -0.172678 0.984964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -9.55278e-05 -0.0279579 3.99997 0.00219027 3.88092 +EDGE_SE3:QUAT 138 1501 3.7824 -0.701915 -0.0110752 0.00265046 0.00132297 -0.191645 0.98146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 7.59069e-06 0.0159523 3.99998 -0.00170383 3.85315 +EDGE_SE3:QUAT 139 1501 -0.205342 0.103826 0.00299594 0.00209107 0.000945995 0.0195983 0.999805 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.60024e-06 0.00707192 4 6.77192e-05 3.99848 +EDGE_SE3:QUAT 140 1501 -4.16754 -0.554154 0.0236546 -0.00364256 0.00460809 0.196711 0.980444 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00041 4.87224e-05 0.0431265 3.99989 0.00444996 3.84568 +EDGE_SE3:QUAT 183 1501 2.84522 4.81598 0.093848 0.001895 -0.0147724 0.917799 0.396766 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 -8.52178e-05 -0.016527 4.00047 0.0321002 0.630158 +EDGE_SE3:QUAT 184 1501 -1.20274 4.89486 0.0604334 -0.00025852 -0.012281 0.916541 0.399752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000173686 -0.00502587 4 0.0313332 0.639556 +EDGE_SE3:QUAT 1429 1501 3.12437 -3.39074 -0.0125077 -0.00251679 0.0029882 -0.407837 0.913046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.91274e-05 0.00724476 4.00001 -0.000195398 3.33468 +EDGE_SE3:QUAT 1430 1501 -0.903729 -3.30112 -0.0234239 -0.00192957 0.003115 -0.409602 0.912257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.42226e-05 0.0104958 4.00001 -0.00102867 3.32892 +EDGE_SE3:QUAT 1431 1501 -5.06175 -3.23044 -0.0195681 -0.00404464 0.00310685 -0.407233 0.91331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.02687e-05 0.00135521 4 0.00151882 3.33663 +EDGE_SE3:QUAT 1502 1503 4.34052 -0.686003 -0.0201308 0.00737703 0.0193385 -0.121719 0.992349 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00635 -0.000575019 0.162181 3.99841 -0.00998801 3.9473 +EDGE_SE3:QUAT 139 1502 3.89252 -0.524481 -0.00630059 0.00483943 -0.00325553 -0.15327 0.988167 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -5.14961e-05 -0.0163697 3.99999 0.00100401 3.9061 +EDGE_SE3:QUAT 140 1502 -0.129847 0.275511 -0.00127209 -0.000465005 0.000126588 0.0247271 0.999694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.66312e-07 0.0011497 4 1.4779e-05 3.99755 +EDGE_SE3:QUAT 141 1502 -4.51189 -0.0589338 -0.15666 -0.00644983 -0.0193819 0.131783 0.991068 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00479 0.00147704 -0.141083 3.99894 -0.00906619 3.93549 +EDGE_SE3:QUAT 1430 1502 1.18954 -6.85427 -0.0209159 -0.00151472 -0.00277144 -0.561134 0.827719 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -9.30565e-05 -0.0206324 4.00003 0.00546189 2.74061 +EDGE_SE3:QUAT 1431 1502 -2.91597 -6.78037 -0.0173908 -0.0036876 -0.00314978 -0.558908 0.829216 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00023 -0.000190194 -0.0339521 4.00002 0.0102852 2.75077 +EDGE_SE3:QUAT 1503 1504 4.30824 -0.409858 0.0066847 -0.00348839 -0.00617745 -0.0648545 0.99787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 2.77134e-05 -0.0518223 3.99983 0.00170368 3.98385 +EDGE_SE3:QUAT 140 1503 4.25632 -0.188919 -0.023682 0.00615752 0.0195168 -0.0974538 0.99503 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00634 -0.00043782 0.161298 3.99841 -0.00791351 3.9685 +EDGE_SE3:QUAT 141 1503 -0.143635 0.415529 -0.00334237 0.000679536 8.4853e-05 0.00993228 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.95319e-07 0.000597737 4 2.8343e-06 3.99961 +EDGE_SE3:QUAT 142 1503 -4.53328 0.334669 0.0553387 0.00594109 0.00667969 0.0519401 0.99861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 0.000192837 0.0495286 3.99986 0.00125852 3.98982 +EDGE_SE3:QUAT 1504 1505 4.18934 -0.154053 0.00609846 -0.000776347 -0.00467313 -0.0097982 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 9.40624e-06 -0.0374738 3.99991 0.000183362 3.99997 +EDGE_SE3:QUAT 141 1504 4.16038 0.108201 -0.000805495 -0.00275852 -0.00596232 -0.0546953 0.998481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00058 1.95509e-05 -0.0492978 3.99985 0.00136077 3.98864 +EDGE_SE3:QUAT 142 1504 -0.219254 0.36207 0.00199743 0.00212165 0.000719113 -0.0128145 0.999915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.38892e-06 0.00607768 4 -3.96064e-05 3.99935 +EDGE_SE3:QUAT 143 1504 -4.29587 0.40863 0.0260223 0.000871296 0.00471696 0.00141085 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 1.7189e-05 0.0377237 3.99991 2.70791e-05 4.00035 +EDGE_SE3:QUAT 1505 1506 4.45609 -0.106564 0.00580887 0.0018821 0.00133598 -0.00143177 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.00369e-05 0.0107201 3.99999 -7.60124e-06 4.00002 +EDGE_SE3:QUAT 142 1505 3.95809 0.115669 0.000830126 0.00131552 -0.00414314 -0.0230189 0.999726 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 -3.07786e-05 -0.0327574 3.99993 0.000376124 3.99815 +EDGE_SE3:QUAT 143 1505 -0.0953111 0.271571 -0.00560625 -3.65967e-05 -7.90477e-05 -0.00899043 0.99996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.03047e-08 -0.000636253 4 2.86589e-06 3.99968 +EDGE_SE3:QUAT 144 1505 -4.33913 0.357858 -0.0271086 -0.00113457 -0.00159522 -0.00494047 0.999986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.98609e-06 -0.0128286 3.99999 3.16758e-05 3.99994 +EDGE_SE3:QUAT 1506 1507 4.45376 -0.109322 0.0148595 0.000123855 -0.00108009 -0.0012964 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -5.71226e-07 -0.00863878 4 5.60276e-06 4.00001 +EDGE_SE3:QUAT 143 1506 4.34936 0.0832896 0.00164469 0.00175217 0.00130206 -0.0104121 0.999943 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 8.94213e-06 0.0106337 3.99999 -5.56642e-05 3.99959 +EDGE_SE3:QUAT 144 1506 0.137192 0.200402 -0.00285042 0.000512092 -0.000412968 -0.0061324 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.57638e-07 -0.00326587 4 9.97718e-06 3.99985 +EDGE_SE3:QUAT 145 1506 -4.19679 0.288007 -0.0117944 -0.000755381 0.000424879 -0.00196634 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.28325e-06 0.00338119 4 -3.32169e-06 3.99999 +EDGE_SE3:QUAT 1507 1508 4.38169 -0.0989012 0.0172347 0.000506375 -0.000342582 -0.000948651 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.94616e-07 -0.00273488 4 1.29774e-06 4 +EDGE_SE3:QUAT 144 1507 4.56985 0.0416655 0.0146055 0.000353343 -0.00141856 -0.00745191 0.999971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -2.35565e-06 -0.011316 3.99999 4.21405e-05 3.99981 +EDGE_SE3:QUAT 145 1507 0.252883 0.154707 -0.00366453 -0.000615589 -0.000627428 -0.00337956 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.52299e-06 -0.00504431 4 8.53197e-06 3.99996 +EDGE_SE3:QUAT 146 1507 -4.13597 0.238579 -0.0108738 -0.00069506 0.00113574 0.000757993 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -3.13713e-06 0.0090923 3.99999 3.42525e-06 4.00002 +EDGE_SE3:QUAT 1508 1509 4.45249 -0.101723 0.0165883 -0.00179171 0.0106672 -0.00224293 0.999939 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00181 -8.26361e-05 0.0853223 3.99955 -0.000100673 4.0018 +EDGE_SE3:QUAT 145 1508 4.64113 0.0243708 0.0199218 -2.92239e-07 -0.000926882 -0.00437188 0.99999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -8.90565e-08 -0.00741488 4 1.62085e-05 3.99994 +EDGE_SE3:QUAT 146 1508 0.276637 0.135633 -0.000329432 -0.000369178 0.000750237 -0.000384967 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.11267e-06 0.0060002 4 -1.15982e-06 4.00001 +EDGE_SE3:QUAT 147 1508 -4.19271 0.214149 -0.0942467 0.00207224 -0.00852471 0.00335655 0.999956 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00115 -6.49791e-05 -0.068297 3.99971 -0.000111132 4.00112 +EDGE_SE3:QUAT 1509 1510 4.33262 -0.0967435 0.000428933 -4.85864e-05 0.00317954 0.000247452 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -5.57978e-07 0.0254373 3.99996 3.13581e-06 4.00016 +EDGE_SE3:QUAT 146 1509 4.707 0.0443766 0.00714708 -0.00219987 0.0115375 -0.00278032 0.999927 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00211 -0.000110479 0.0922676 3.99947 -0.000135434 4.0021 +EDGE_SE3:QUAT 147 1509 0.256673 0.147524 0.0056942 1.18938e-05 0.0023225 0.00134073 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 2.84067e-07 0.0185801 3.99998 1.24576e-05 4.00008 +EDGE_SE3:QUAT 148 1509 -3.73614 0.220575 -0.00926211 0.000185497 -0.00127986 0.00400984 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -7.92885e-07 -0.0102476 3.99999 -2.05445e-05 3.99996 +EDGE_SE3:QUAT 1510 1511 3.9896 -0.0743807 0.0125094 -0.00218518 -0.00562777 0.00113664 0.999981 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00049 5.00317e-05 -0.0449969 3.99987 -2.72349e-05 4.0005 +EDGE_SE3:QUAT 147 1510 4.58791 0.0570159 -0.0174516 0.000116937 0.00515267 0.00157792 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00042 3.41635e-06 0.0412228 3.99989 3.26062e-05 4.00041 +EDGE_SE3:QUAT 148 1510 0.596384 0.159274 -0.00213464 0.000347815 0.00171165 0.00458639 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.69869e-06 0.0136738 3.99999 3.1367e-05 3.99996 +EDGE_SE3:QUAT 149 1510 -3.42006 0.242081 0.0146668 0.00223397 0.00454488 0.00706559 0.999962 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00031 4.3812e-05 0.0361692 3.99992 0.000128678 4.00013 +EDGE_SE3:QUAT 1511 1512 4.02757 -0.066913 0.0168848 -0.0019982 -0.000841725 0.00214002 0.999995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.69529e-06 -0.00668241 4 -7.16556e-06 3.99999 +EDGE_SE3:QUAT 148 1511 4.56292 0.121431 -0.00189921 -0.00200153 -0.00381405 0.00577662 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00021 3.23569e-05 -0.0303735 3.99994 -8.83e-05 4.0001 +EDGE_SE3:QUAT 149 1511 0.543899 0.229734 -0.0141404 5.60229e-05 -0.0011702 0.00857274 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.95627e-08 -0.0093664 3.99999 -4.01533e-05 3.99973 +EDGE_SE3:QUAT 150 1511 -4.00354 0.308503 -0.0129146 0.00247493 0.000504635 0.0111553 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.50759e-06 0.00370502 4 2.00612e-05 3.99951 +EDGE_SE3:QUAT 1512 1513 4.47121 -0.0577464 0.0227179 -0.00178393 -0.000429213 0.00363068 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.98571e-06 -0.0033559 4 -6.05265e-06 3.99995 +EDGE_SE3:QUAT 149 1512 4.56541 0.229435 0.0118888 -0.00205718 -0.00196142 0.0108448 0.999937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 1.67445e-05 -0.015421 3.99999 -8.33178e-05 3.99959 +EDGE_SE3:QUAT 150 1512 0.0252368 0.338876 -0.00158428 0.000532399 -0.000329693 0.0135001 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.95447e-07 -0.00272306 4 -1.85717e-05 3.99927 +EDGE_SE3:QUAT 151 1512 -4.3774 0.421542 -0.0229968 0.000436332 0.000503807 0.0152211 0.999884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.45577e-07 0.00394937 4 2.98538e-05 3.99908 +EDGE_SE3:QUAT 1513 1514 4.29015 -0.0766868 0.0303695 -0.000545479 -0.00154917 0.00365211 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 3.58121e-06 -0.0123693 3.99999 -2.26042e-05 3.99998 +EDGE_SE3:QUAT 150 1513 4.49695 0.38725 0.0187249 -0.0012617 -0.000752498 0.0167917 0.999858 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.79511e-06 -0.00576325 4 -4.7685e-05 3.99888 +EDGE_SE3:QUAT 151 1513 0.0951346 0.490386 -0.00897426 -0.00156852 9.72741e-05 0.0187655 0.999823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.71366e-07 0.00113091 4 1.17138e-05 3.99859 +EDGE_SE3:QUAT 152 1513 -4.09167 0.575253 -0.0438073 -0.00249076 -0.000646452 0.0206673 0.999783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.57994e-06 -0.00455071 4 -4.49068e-05 3.9983 +EDGE_SE3:QUAT 1514 1515 4.05476 -0.107405 0.0260539 0.00886357 -0.00315648 0.00372525 0.999949 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000113335 -0.0256455 3.99996 -4.58456e-05 4.00011 +EDGE_SE3:QUAT 151 1514 4.37879 0.56594 0.0219202 -0.00199337 -0.0014891 0.0225403 0.999743 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.22607e-05 -0.0113648 3.99999 -0.000126124 3.998 +EDGE_SE3:QUAT 152 1514 0.190976 0.677966 -0.00831736 -0.00287471 -0.00215458 0.0243145 0.999698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.56449e-05 -0.016383 3.99998 -0.000196015 3.9977 +EDGE_SE3:QUAT 153 1514 -4.22616 0.787351 0.000130416 -0.0065887 0.00277964 0.0260282 0.999636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -7.66582e-05 0.0242709 3.99996 0.000323312 3.99744 +EDGE_SE3:QUAT 1515 1516 4.35829 -0.0820853 0.0217836 -0.00128456 0.00125777 -0.00985026 0.99995 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -6.69673e-06 0.00990885 3.99999 -4.85991e-05 3.99964 +EDGE_SE3:QUAT 152 1515 4.25054 0.786035 0.030142 0.00609715 -0.0050019 0.0284792 0.999563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00029 -0.00011181 -0.042051 3.99989 -0.000604648 3.9972 +EDGE_SE3:QUAT 153 1515 -0.157253 0.886618 0.00226599 0.00249337 -0.000103597 0.0301459 0.999542 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.50363e-06 -0.00172907 4 -3.05862e-05 3.99637 +EDGE_SE3:QUAT 154 1515 -4.15284 0.996879 -0.0343096 0.00115589 -0.00113589 0.0267659 0.99964 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.64923e-06 -0.00944846 3.99999 -0.000128025 3.99716 +EDGE_SE3:QUAT 1516 1517 4.25253 -0.343321 0.0369883 -0.000333014 0.0136746 -0.0881114 0.996017 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0029 -0.0004061 0.107843 3.9993 -0.00473782 3.97185 +EDGE_SE3:QUAT 153 1516 4.19044 1.06911 0.0187834 0.00126064 0.00121741 0.0201733 0.999795 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 6.56006e-06 0.0094283 3.99999 9.40978e-05 3.99839 +EDGE_SE3:QUAT 154 1516 0.209678 1.16526 -0.000647219 7.07285e-05 0.000158313 0.0170696 0.999854 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.41603e-08 0.00125147 4 1.06383e-05 3.99883 +EDGE_SE3:QUAT 155 1516 -3.74272 1.48916 -0.109424 -0.00180999 -0.00871404 -0.0250227 0.999647 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00122 1.76127e-05 -0.0702088 3.99969 0.00087777 3.99873 +EDGE_SE3:QUAT 1517 1518 3.99713 -0.690226 0.0117817 -0.00391043 -0.00496477 -0.183922 0.982921 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00047 -4.5934e-05 -0.0461609 3.99987 0.00444441 3.86522 +EDGE_SE3:QUAT 154 1517 4.45558 0.967751 0.0392051 -0.000310391 0.0139344 -0.0708462 0.99739 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00305 -0.000343322 0.110447 3.99926 -0.00390867 3.98297 +EDGE_SE3:QUAT 155 1517 0.462655 0.918073 0.00833792 -0.000866533 0.00478603 -0.113035 0.993579 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00033 -7.33016e-05 0.0363939 3.99992 -0.00202171 3.94922 +EDGE_SE3:QUAT 156 1517 -3.59542 1.62754 0.00493816 -0.000679715 0.00569487 -0.26045 0.96547 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 -0.00017719 0.0389773 3.99995 -0.00477422 3.72904 +EDGE_SE3:QUAT 1518 1519 4.01232 -0.907051 0.00282933 0.00356374 3.62754e-05 -0.214565 0.976703 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 1.75189e-05 0.00916458 3.99999 -0.00131017 3.81587 +EDGE_SE3:QUAT 155 1518 4.20277 -0.619905 -0.00595639 -0.00568954 -0.000194242 -0.293889 0.955823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 4.62296e-05 -0.0202668 3.99996 0.00394607 3.65461 +EDGE_SE3:QUAT 156 1518 -0.503815 -0.967875 -0.0165065 -0.00626529 0.00155942 -0.433287 0.901233 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 6.97271e-05 -0.0193663 3.99994 0.00679249 3.24912 +EDGE_SE3:QUAT 157 1518 -5.09836 0.415198 -0.0549653 -0.00144548 0.00321165 -0.613457 0.789721 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.26789e-05 0.00468315 4.00001 0.00148756 2.49467 +EDGE_SE3:QUAT 1456 1518 3.68745 -5.85518 -0.0202111 -0.00535755 -0.00349487 0.495231 0.868738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -6.39219e-05 0.00830105 3.99997 0.00560524 3.01897 +EDGE_SE3:QUAT 1457 1518 -0.552134 -5.74317 -0.0364085 -0.00554632 -0.00374419 0.49493 0.868907 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -6.74484e-05 0.00790992 3.99997 0.0056637 3.02016 +EDGE_SE3:QUAT 1458 1518 -4.68727 -5.62598 -0.0596475 -0.00645595 -0.00342197 0.490598 0.871355 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -9.37551e-05 0.013796 3.99994 0.00734969 3.03726 +EDGE_SE3:QUAT 1519 1520 4.12661 -0.963441 0.000992738 0.00390429 0.00739849 -0.197132 0.980341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00099 -0.000174321 0.0647829 3.99976 -0.00657017 3.8456 +EDGE_SE3:QUAT 156 1519 1.29462 -4.64178 0.0119077 -0.00336948 -0.00142971 -0.616607 0.787263 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -8.80908e-05 -0.0241942 4.00001 0.00891371 2.47933 +EDGE_SE3:QUAT 157 1519 -4.98108 -3.69874 -0.0581935 0.000721787 0.000379083 -0.768728 0.639575 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.29276e-06 0.0048286 4 -0.0019704 1.63624 +EDGE_SE3:QUAT 1456 1519 6.53349 -2.85081 0.00190297 -0.00110037 -0.00264745 0.296933 0.954894 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 3.69755e-05 -0.0147509 4 -0.00184906 3.64738 +EDGE_SE3:QUAT 1457 1519 2.2966 -2.75833 -0.0127687 -0.00148524 -0.00303262 0.296515 0.955022 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 4.68385e-05 -0.0161578 4 -0.00196704 3.64838 +EDGE_SE3:QUAT 1458 1519 -1.85431 -2.67598 -0.0278823 -0.00170864 -0.00273628 0.291828 0.956465 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 3.55525e-05 -0.0135104 4 -0.00153685 3.65939 +EDGE_SE3:QUAT 1459 1519 -5.99815 -2.54245 -0.12091 -0.00635798 -0.0108869 0.289045 0.957232 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00057 0.000577686 -0.0555839 3.99998 -0.00643114 3.66654 +EDGE_SE3:QUAT 1520 1521 4.08468 -0.323312 0.00692657 0.00253819 0.00502025 -0.0162952 0.999851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 4.17569e-05 0.0406456 3.9999 -0.000330991 3.99935 +EDGE_SE3:QUAT 1457 1520 6.23975 -1.21208 0.0158557 0.000726423 0.00501519 0.102546 0.994715 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00037 7.24572e-05 0.0386057 3.99991 0.00195416 3.95831 +EDGE_SE3:QUAT 1458 1520 2.13083 -1.1684 0.00191624 0.0005989 0.00508086 0.0981923 0.995154 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00039 6.98175e-05 0.0393626 3.99991 0.00191217 3.96182 +EDGE_SE3:QUAT 1459 1520 -2.03229 -1.07124 -0.023422 -0.00229799 -0.00365104 0.0944237 0.995523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 5.47072e-05 -0.0262309 3.99996 -0.00119202 3.96451 +EDGE_SE3:QUAT 1460 1520 -6.36025 -0.936772 -0.00204338 -0.00156998 -0.00218417 0.0918076 0.995773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 2.04906e-05 -0.0155331 3.99999 -0.000683345 3.96635 +EDGE_SE3:QUAT 1521 1522 4.34257 0.431855 0.015262 0.00197163 -0.00175422 0.178786 0.983884 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 6.80787e-07 -0.0175064 3.99998 -0.00167024 3.87222 +EDGE_SE3:QUAT 918 1521 3.93489 -6.2654 -0.0069358 -0.00218956 -0.00188827 0.768041 0.640394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.28433e-05 0.0082767 3.99998 0.00766 1.64046 +EDGE_SE3:QUAT 919 1521 -0.111704 -6.16735 -0.0171377 -0.00201743 -0.00132819 0.767161 0.64145 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.62739e-06 0.0084809 3.99998 0.00681463 1.64587 +EDGE_SE3:QUAT 920 1521 -4.16876 -6.05283 0.196991 0.0182407 0.0164899 0.766158 0.642181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99939 -0.000997833 -0.0670881 3.99837 -0.0638563 1.65273 +EDGE_SE3:QUAT 1458 1521 6.19692 -0.690893 -0.0389219 0.00255264 0.0103561 0.0818289 0.996589 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00155 0.000298628 0.0795482 3.99963 0.00321878 3.9748 +EDGE_SE3:QUAT 1459 1521 2.04091 -0.603571 0.00660964 8.12293e-05 0.00142585 0.0784325 0.996918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.19789e-06 0.0112257 3.99999 0.00043786 3.97542 +EDGE_SE3:QUAT 1460 1521 -2.27262 -0.500375 0.017581 0.000667195 0.00290573 0.0758223 0.997117 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00012 2.19867e-05 0.0224415 3.99997 0.00084077 3.97713 +EDGE_SE3:QUAT 1461 1521 -6.62364 -0.400781 0.0362476 4.35096e-05 0.00371214 0.074207 0.997236 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00022 2.48844e-05 0.0294149 3.99995 0.00108804 3.97819 +EDGE_SE3:QUAT 1522 1523 4.15279 1.09405 0.0161152 -0.000614039 -0.00407958 0.286251 0.958146 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00017 9.49938e-05 -0.0267154 3.99998 -0.00352084 3.67242 +EDGE_SE3:QUAT 917 1522 6.74119 -2.14965 -0.0441817 0.00447171 0.00262205 0.870746 0.491705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 4.77949e-05 -0.0206135 3.99997 -0.0180538 0.96731 +EDGE_SE3:QUAT 918 1522 2.72787 -2.07591 0.00235613 0.000139395 -0.0010495 0.870146 0.492793 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.16346e-06 -0.00172559 4 0.00146262 0.971382 +EDGE_SE3:QUAT 919 1522 -1.29708 -1.98744 -0.00547147 0.000585441 -0.000255579 0.869651 0.493667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.54481e-06 -0.00327514 4 -0.00129291 0.974831 +EDGE_SE3:QUAT 920 1522 -5.3503 -1.8777 0.258029 0.0233359 0.0130578 0.868884 0.494293 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00075 0.00138793 -0.108281 3.99945 -0.0929469 0.98309 +EDGE_SE3:QUAT 1459 1522 6.26379 0.485039 0.00633642 0.00200402 -0.000159466 0.255467 0.966816 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.75692e-06 -0.00702913 4 -0.00115325 3.73896 +EDGE_SE3:QUAT 1460 1522 1.94119 0.57233 0.00803189 0.00332833 0.0011257 0.252769 0.96752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -8.68562e-06 -0.00150925 4 -0.000653289 3.74443 +EDGE_SE3:QUAT 1461 1522 -2.40827 0.658117 0.0232245 0.00288615 0.00214755 0.251087 0.967958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 1.38887e-05 0.00725076 4 0.000475984 3.74783 +EDGE_SE3:QUAT 1462 1522 -6.72509 0.71389 -0.0208207 0.00379416 -0.00128759 0.254395 0.967092 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 -1.26725e-05 -0.0204003 3.99997 -0.00304004 3.74124 +EDGE_SE3:QUAT 1523 1524 4.07657 0.757486 -0.0672218 -0.00434231 0.0194726 0.17891 0.983663 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00613 0.00134114 0.1577 3.99864 0.0141747 3.87817 +EDGE_SE3:QUAT 917 1523 3.66457 0.850965 0.00290709 0.00853297 -0.00110632 0.974916 0.222405 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 0.00034296 -0.0366669 4.00109 -0.0105494 0.198235 +EDGE_SE3:QUAT 918 1523 -0.327376 0.924977 0.0238837 0.00290258 -0.00377122 0.974798 0.223038 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 1.05564e-05 -0.0127784 4.00019 0.00832091 0.199046 +EDGE_SE3:QUAT 919 1523 -4.3619 1.00056 0.0248558 0.00362148 -0.00315032 0.97451 0.224294 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 3.9568e-05 -0.0158213 4.00027 0.00487362 0.201304 +EDGE_SE3:QUAT 1460 1523 5.02097 3.55042 0.03148 0.00398072 -0.00379583 0.518998 0.854758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 0.000232559 -0.0393085 4.00001 -0.0109687 2.92295 +EDGE_SE3:QUAT 1461 1523 0.686483 3.63054 0.0392738 0.00414076 -0.0030102 0.517816 0.855477 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00026 0.000172995 -0.0362109 3.99999 -0.0104908 2.92779 +EDGE_SE3:QUAT 1462 1523 -3.67068 3.71405 0.0312661 0.00382504 -0.0066514 0.52041 0.853882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00062 0.000525664 -0.0527143 4.00009 -0.0134291 2.91737 +EDGE_SE3:QUAT 1524 1525 4.04904 0.114472 0.0346484 0.0035329 -0.0013342 0.0403048 0.99918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -2.06437e-05 -0.0123544 3.99999 -0.000260088 3.99354 +EDGE_SE3:QUAT 916 1524 3.67856 1.85143 0.053777 -0.00617058 -0.00507833 0.999027 0.0433646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 0.000152256 0.0247495 4.00044 0.0223586 0.00780052 +EDGE_SE3:QUAT 917 1524 -0.32783 1.95525 0.0127156 -0.0116286 -0.0025061 0.998943 0.0443938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99949 0.000254543 0.0466486 4.00206 0.0141077 0.00847817 +EDGE_SE3:QUAT 918 1524 -4.29992 2.02121 -0.0205991 -0.0177562 -0.00410759 0.998824 0.0449177 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99881 0.000616654 0.0712317 4.00479 0.0227561 0.00947111 +EDGE_SE3:QUAT 1525 1526 4.03555 -0.0757694 0.0294033 -0.00278998 0.000221257 0.0100507 0.999946 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -3.07897e-06 0.00210624 4 1.11435e-05 3.9996 +EDGE_SE3:QUAT 915 1525 3.78632 2.0229 0.0330965 0.0051141 0.00151439 -0.999964 0.00666877 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 2.69043e-05 0.0204575 4.00041 0.00578486 0.00029089 +EDGE_SE3:QUAT 916 1525 -0.317125 2.10087 0.0368475 -0.00504131 -0.00158213 0.999981 0.00319323 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 3.37939e-05 0.0201654 4.0004 0.00645803 0.000152876 +EDGE_SE3:QUAT 917 1525 -4.31315 2.19414 -0.0457955 -0.0105992 0.00125896 0.999934 0.00423895 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99955 -4.20633e-05 0.0423955 4.00179 -0.00467903 0.000526748 +EDGE_SE3:QUAT 1526 1527 4.11077 -0.00876317 -1.61099e-05 0.00169575 -0.00288499 0.0483048 0.998827 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -1.03337e-05 -0.0239813 3.99996 -0.00058616 3.99081 +EDGE_SE3:QUAT 914 1526 4.18225 1.8355 0.0258116 0.00376031 0.00825367 -0.999959 0.000847375 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 0.000124326 0.0150427 3.99995 0.0329906 0.000331534 +EDGE_SE3:QUAT 915 1526 -0.25338 2.04941 0.0180934 0.00534743 0.004355 -0.999833 0.0169132 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 8.37221e-05 0.0213992 4.0004 0.0166867 0.00132837 +EDGE_SE3:QUAT 916 1526 -4.32267 2.18104 0.0249852 0.00527483 0.00417331 -0.999951 0.00732803 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 8.41377e-05 0.0211012 4.00038 0.0163842 0.000393229 +EDGE_SE3:QUAT 1527 1528 4.15163 0.530384 -0.0499012 0.00389267 -0.00105386 0.17584 0.984411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.25079e-05 -0.0160874 3.99998 -0.00164301 3.87638 +EDGE_SE3:QUAT 913 1527 4.62371 0.792887 -0.0228535 0.00752958 -0.0091302 0.991961 0.125992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99965 -0.000118092 -0.030972 4.00098 0.0276207 0.0639349 +EDGE_SE3:QUAT 914 1527 0.0842526 1.80954 0.00122486 0.00149005 0.00636591 -0.998779 0.048957 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 4.95933e-05 0.00598797 3.9999 0.024729 0.00974941 +EDGE_SE3:QUAT 915 1527 -4.34826 1.92946 -0.0197953 0.00299844 0.00233926 -0.997845 0.0655006 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 1.49318e-05 0.0120759 4.00014 0.00769274 0.0172128 +EDGE_SE3:QUAT 1528 1529 4.30188 0.656382 0.00899054 -0.00444656 -0.0159912 0.181667 0.98322 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00305 0.00116436 -0.112233 3.99941 -0.00975148 3.87112 +EDGE_SE3:QUAT 912 1528 5.10345 -0.77737 0.136999 -0.0169703 0.0129243 0.944948 0.326523 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99888 0.00205354 0.0814229 4.00588 0.00119753 0.428322 +EDGE_SE3:QUAT 913 1528 0.475308 1.34172 0.00423968 -0.00687447 0.0071927 -0.998674 0.0505084 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000226175 -0.0275979 4.00043 0.0313644 0.0106417 +EDGE_SE3:QUAT 914 1528 -4.00159 0.914269 -0.0616521 0.00195475 0.00220323 -0.974547 0.224163 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.83947e-06 0.00858428 4.00008 0.0043963 0.201022 +EDGE_SE3:QUAT 1529 1530 4.55167 0.645048 -0.0788162 0.00897029 0.00762954 0.159942 0.987056 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 0.000286415 0.0417813 3.99994 0.0028272 3.8981 +EDGE_SE3:QUAT 911 1529 5.8705 0.139291 -0.00489521 0.00364574 0.000550503 0.942745 0.333495 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 8.03315e-05 -0.0166432 4.00012 -0.0102597 0.444977 +EDGE_SE3:QUAT 912 1529 1.3342 1.35679 -0.00523478 -0.000922292 0.00669834 0.988715 0.149656 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -6.14789e-05 0.003991 3.99991 -0.0242255 0.0897424 +EDGE_SE3:QUAT 913 1529 -3.72022 0.257824 0.0682506 -0.0214724 0.0113412 -0.972519 0.231553 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9995 -0.00231967 -0.0914662 4.00348 0.0771679 0.218171 +EDGE_SE3:QUAT 1530 1531 4.31137 0.400326 -0.0548951 0.00588634 0.00657937 0.107991 0.994113 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00035 0.000207832 0.0441494 3.9999 0.00223542 3.95384 +EDGE_SE3:QUAT 910 1530 6.27977 2.11382 -0.055381 0.00193775 0.0143324 0.974474 0.224034 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000242064 -0.00702024 3.99927 -0.0535573 0.201536 +EDGE_SE3:QUAT 911 1530 1.93622 2.52224 -0.049654 -0.00082664 0.0113214 0.983915 0.178278 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000173258 0.00397531 3.9997 -0.0405857 0.127564 +EDGE_SE3:QUAT 912 1530 -3.22926 2.09495 -0.0812017 0.00656629 -0.0168791 -0.999776 0.0109861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000428802 0.0262804 3.99949 -0.0680784 0.00181433 +EDGE_SE3:QUAT 1531 1532 4.19325 0.224794 -0.0369421 -0.00147593 -0.000749803 0.0663417 0.997796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.87093e-06 -0.00478732 4 -0.000145383 3.9824 +EDGE_SE3:QUAT 909 1531 6.56472 3.41281 -0.0758963 0.00030003 0.0196164 0.991027 0.132217 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000357851 -0.000862 3.99864 -0.0753575 0.0713727 +EDGE_SE3:QUAT 910 1531 2.23306 3.63084 -0.107788 -0.00173577 0.0211471 0.992844 0.117515 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000500914 0.00737069 3.99865 -0.0800648 0.0568807 +EDGE_SE3:QUAT 911 1531 -2.21693 3.65998 -0.114819 -0.00490474 0.0181677 0.997315 0.0707694 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 -0.000470229 0.0198271 3.99941 -0.0690045 0.0213291 +EDGE_SE3:QUAT 1532 1533 4.56712 0.0579362 -0.0420548 -0.00255161 0.000990367 0.0297021 0.999555 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.08085e-05 0.00882133 3.99999 0.000135386 3.99649 +EDGE_SE3:QUAT 909 1532 2.4628 4.2935 -0.122185 0.00236867 0.01772 0.997642 0.0662559 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.76771e-06 -0.00949721 3.99874 -0.0713419 0.0188604 +EDGE_SE3:QUAT 910 1532 -1.85622 4.38714 -0.167279 0.000172348 0.01962 0.998459 0.0519046 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000144907 -0.00066753 3.99849 -0.0780086 0.0123025 +EDGE_SE3:QUAT 1533 1534 4.99901 0.000223587 -0.024812 -0.0046832 0.00167325 0.0102988 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -3.24058e-05 0.0139623 3.99999 7.2553e-05 3.99962 +EDGE_SE3:QUAT 908 1533 2.23074 4.73677 -0.103798 0.00230971 0.0127379 0.999142 0.0393497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.90424e-05 -0.00925572 3.99939 -0.051477 0.00687862 +EDGE_SE3:QUAT 909 1533 -2.05423 4.83082 -0.145353 0.00134079 0.0148949 0.999221 0.0365272 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.52821e-05 -0.00536889 3.99912 -0.0597658 0.00623854 +EDGE_SE3:QUAT 1534 1535 4.11134 -0.0856194 -0.0248343 -0.00122748 -0.00060169 0.00111919 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.95042e-06 -0.00479702 4 -2.69193e-06 4 +EDGE_SE3:QUAT 906 1534 5.59836 5.03831 -0.0656016 0.00128637 0.00741899 0.999887 0.0129867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.28693e-05 -0.00514705 3.9998 -0.0297965 0.000903251 +EDGE_SE3:QUAT 907 1534 1.69029 5.059 -0.0986172 -0.000496623 0.00851721 0.999672 0.0241341 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.05857e-05 0.00198951 3.99972 -0.0339223 0.00261867 +EDGE_SE3:QUAT 908 1534 -2.73417 5.13898 -0.1089 0.000625632 0.00807522 0.99954 0.0292331 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 5.01293e-06 -0.00250424 3.99974 -0.032377 0.00368216 +EDGE_SE3:QUAT 1535 1536 4.30738 -0.0975779 -0.0238632 0.00133465 0.00122223 0.00145622 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 6.55637e-06 0.00975452 3.99999 7.14448e-06 4.00002 +EDGE_SE3:QUAT 905 1535 5.44764 5.29525 -0.0978771 -9.42967e-05 -0.0114472 -0.999915 0.00621777 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.08291e-05 -0.000377379 3.99948 -0.0457765 0.00067864 +EDGE_SE3:QUAT 906 1535 1.51867 5.23342 -0.0875367 0.00187279 0.00638049 0.9999 0.0124592 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.46701e-05 -0.00749324 3.99989 -0.0256986 0.000800104 +EDGE_SE3:QUAT 907 1535 -2.4106 5.32882 -0.130413 -0.000234104 0.00754075 0.999705 0.0230967 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.74512e-05 0.000938065 3.99978 -0.0300787 0.00236036 +EDGE_SE3:QUAT 1536 1537 4.52093 -0.0970433 -0.0320331 1.50139e-05 0.000534929 0.00218267 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.71086e-08 0.00427901 4 4.6698e-06 3.99999 +EDGE_SE3:QUAT 904 1536 5.47222 5.25986 -0.0891501 -0.00111454 -0.0102448 -0.999854 0.013603 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 5.65356e-05 -0.00446039 3.99961 -0.0408372 0.00116218 +EDGE_SE3:QUAT 905 1536 1.15907 5.34925 -0.130846 0.00113621 -0.0125028 -0.999895 0.00719761 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.79839e-05 0.00454611 3.99939 -0.0500667 0.000839185 +EDGE_SE3:QUAT 906 1536 -2.78808 5.4453 -0.089586 0.000977312 0.0075931 0.999914 0.010689 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.49433e-05 -0.00391015 3.99978 -0.0304466 0.000692628 +EDGE_SE3:QUAT 1537 1538 4.65093 -0.0963214 -0.0267361 -0.00127676 0.00131593 0.00167357 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -6.6726e-06 0.0105531 3.99999 8.7847e-06 4.00002 +EDGE_SE3:QUAT 903 1537 5.17952 5.13528 -0.0823002 5.43843e-05 -0.00951145 -0.999843 0.0149259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 8.72879e-06 0.000217284 3.99964 -0.0380294 0.00125282 +EDGE_SE3:QUAT 904 1537 0.946196 5.24009 -0.107565 -0.000179404 -0.0101396 -0.999823 0.0158433 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.02492e-05 -0.00071845 3.99959 -0.0405083 0.00141455 +EDGE_SE3:QUAT 905 1537 -3.35834 5.37461 -0.165326 0.00188178 -0.0133773 -0.999864 0.00940681 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.78566e-05 0.00752988 3.99933 -0.0536351 0.00108749 +EDGE_SE3:QUAT 1538 1539 5.10187 -0.116135 -0.0342023 0.00109024 -0.00112491 0.00136057 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.87724e-06 -0.00901706 3.99999 -6.10507e-06 4.00001 +EDGE_SE3:QUAT 902 1538 4.84256 4.98687 -0.0947401 -0.000702754 -0.00899231 -0.999834 0.0158126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.52025e-05 -0.00281278 3.99969 -0.0358566 0.00132366 +EDGE_SE3:QUAT 903 1538 0.509499 5.09476 -0.10759 0.00135992 -0.0088468 -0.999828 0.0162342 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.8482e-05 0.00544208 3.99971 -0.0355393 0.00137747 +EDGE_SE3:QUAT 904 1538 -3.73308 5.19979 -0.134047 0.00126314 -0.00937483 -0.999808 0.0171344 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.57616e-05 0.00505496 3.99967 -0.0376435 0.00153513 +EDGE_SE3:QUAT 1539 1540 5.03287 -0.114194 -0.0218347 0.00134164 0.00195339 0.0008842 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.05516e-05 0.0156131 3.99998 7.02339e-06 4.00006 +EDGE_SE3:QUAT 901 1539 4.03408 4.84768 -0.0923742 -0.00219994 -0.00898927 -0.99982 0.0165359 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 8.7508e-05 -0.00880477 3.99977 -0.0356412 0.00143081 +EDGE_SE3:QUAT 902 1539 -0.287041 4.94094 -0.121441 -0.00187519 -0.0109197 -0.999799 0.0166869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 9.60178e-05 -0.00750577 3.9996 -0.0433967 0.0015989 +EDGE_SE3:QUAT 903 1539 -4.59997 5.0399 -0.156454 0.000369124 -0.00996656 -0.999798 0.0174676 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.36894e-07 0.00147683 3.9996 -0.0398854 0.00161889 +EDGE_SE3:QUAT 1540 1541 5.16678 -0.106495 -0.0220419 -0.00251509 0.000193494 0.000513833 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.97213e-06 0.00156345 4 4.00708e-07 4 +EDGE_SE3:QUAT 900 1540 3.28949 4.68969 -0.110499 -0.0010297 -0.0116847 -0.999798 0.0163137 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 6.52913e-05 -0.00412187 3.99948 -0.0465705 0.00161121 +EDGE_SE3:QUAT 901 1540 -1.01637 4.78688 -0.0926197 -0.000291562 -0.0100883 -0.999801 0.0172343 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.56848e-05 -0.0011675 3.9996 -0.0402813 0.00159423 +EDGE_SE3:QUAT 902 1540 -5.29608 4.89116 -0.12429 0.000462835 -0.012101 -0.99978 0.0171511 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.31518e-06 0.00185183 3.99941 -0.0484283 0.00176409 +EDGE_SE3:QUAT 1541 1542 5.28074 -0.125239 -0.00931881 0.000383904 0.00536133 0.00131232 0.999985 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 9.13992e-06 0.0428888 3.99989 2.8414e-05 4.00045 +EDGE_SE3:QUAT 899 1541 2.30541 4.52424 -0.0874147 0.000921169 -0.00850707 -0.999833 0.0161484 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.22014e-05 0.00368615 3.99972 -0.0341239 0.00133768 +EDGE_SE3:QUAT 900 1541 -1.88277 4.62074 -0.108683 -0.00085351 -0.00966126 -0.999812 0.0167695 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 4.50428e-05 -0.00341643 3.99965 -0.0385018 0.00149852 +EDGE_SE3:QUAT 1542 1543 5.05638 -0.104728 0.0277519 0.000952778 0.000590994 0.00113675 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.25358e-06 0.00471494 4 2.68536e-06 4 +EDGE_SE3:QUAT 897 1542 6.05781 4.27205 -0.0485905 0.00419259 -0.00775345 -0.999835 0.0158732 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000128585 0.0167779 4.00002 -0.0315284 0.00132679 +EDGE_SE3:QUAT 898 1542 1.90279 4.35443 -0.0538429 0.00416522 -0.00628157 -0.999833 0.0166493 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000105887 0.0166685 4.0001 -0.0256653 0.00134299 +EDGE_SE3:QUAT 899 1542 -2.97938 4.47525 -0.107514 0.00653058 -0.00910431 -0.999789 0.0172257 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000243002 0.0261366 4.0003 -0.0372966 0.00170553 +EDGE_SE3:QUAT 1543 1544 5.01592 -0.0945756 0.0308869 -0.00260189 -0.000258331 0.00107818 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.63185e-06 -0.00203296 4 -1.09396e-06 4 +EDGE_SE3:QUAT 896 1543 5.55108 4.12185 -0.0525688 0.00360785 -0.00685574 -0.999773 0.0198254 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -9.70696e-05 0.0144404 4 -0.0279692 0.00181997 +EDGE_SE3:QUAT 897 1543 0.991792 4.20766 -0.0671918 0.00482405 -0.00828569 -0.999808 0.0171105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000159324 0.0193062 4.00007 -0.0337815 0.00154965 +EDGE_SE3:QUAT 898 1543 -3.14653 4.30341 -0.0685391 0.00499323 -0.00688507 -0.999816 0.0172009 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000140668 0.0199828 4.00018 -0.0282098 0.00148233 +EDGE_SE3:QUAT 1544 1545 5.09536 -0.0919255 0.0172786 -0.00185849 -0.000959864 0.00164993 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.1262e-06 -0.00764207 4 -6.33514e-06 4 +EDGE_SE3:QUAT 895 1544 4.84561 3.93392 -0.0449048 0.00277524 -0.00434123 -0.999674 0.0250116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -4.85701e-05 0.0111111 4.00003 -0.0178932 0.0026133 +EDGE_SE3:QUAT 896 1544 0.545339 4.02303 -0.0608152 0.00336684 -0.00470524 -0.999766 0.0208439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -6.49147e-05 0.0134762 4.00008 -0.0193626 0.00187705 +EDGE_SE3:QUAT 897 1544 -3.99976 4.13584 -0.0853134 0.00493288 -0.0061378 -0.999811 0.0177798 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000125551 0.0197416 4.00021 -0.025236 0.0015212 +EDGE_SE3:QUAT 1545 1546 4.76343 -0.0945624 0.0331356 -9.34302e-05 -0.00215957 0.00324629 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 1.17013e-06 -0.017273 3.99998 -2.80462e-05 4.00003 +EDGE_SE3:QUAT 894 1545 4.30738 3.669 -0.073391 0.00230427 -0.00512133 -0.999707 0.0235325 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -4.48563e-05 0.00922453 3.99997 -0.0208908 0.00234556 +EDGE_SE3:QUAT 895 1545 -0.246718 3.7786 -0.0521993 0.00170191 -0.00264437 -0.999634 0.0268736 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.81617e-05 0.00681469 4.00001 -0.0109242 0.00293023 +EDGE_SE3:QUAT 896 1545 -4.53394 3.89309 -0.0692929 0.00221975 -0.00325701 -0.999731 0.0228471 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -2.94436e-05 0.00888579 4.00003 -0.0134168 0.00215273 +EDGE_SE3:QUAT 1546 1547 4.69002 -0.105729 0.000394382 0.00157416 0.0019609 0.00415192 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00005 1.26452e-05 0.0156085 3.99998 3.24936e-05 3.99999 +EDGE_SE3:QUAT 893 1546 4.42255 3.01474 -0.073546 0.00291289 0.0046198 0.9988 0.0486636 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 5.34419e-05 -0.011689 4.00002 -0.0195017 0.0096021 +EDGE_SE3:QUAT 894 1546 -0.4731 3.53973 -0.0558991 4.17398e-05 -0.0050304 -0.999634 0.0265783 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 4.53187e-06 0.00016636 3.9999 -0.0200947 0.00292666 +EDGE_SE3:QUAT 895 1546 -5.00439 3.62769 -0.040029 -0.000104917 -0.00285791 -0.999555 0.0296774 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.10612e-06 -0.000420831 3.99997 -0.0113816 0.00355545 +EDGE_SE3:QUAT 1547 1548 4.66462 -0.0861032 0.0208268 0.00424821 0.00244765 0.00615756 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 4.15655e-05 0.019266 3.99998 5.95913e-05 3.99994 +EDGE_SE3:QUAT 892 1547 5.87564 1.80288 -0.0883637 0.0084154 0.00491647 0.95057 0.310357 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 0.00033703 -0.0369939 4.00029 -0.0339806 0.385953 +EDGE_SE3:QUAT 893 1547 -0.241565 3.56826 -0.0454263 0.00103318 0.0063575 0.999002 0.0441912 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.24173e-05 -0.00414059 3.99984 -0.02567 0.00798081 +EDGE_SE3:QUAT 894 1547 -5.13598 3.38433 -0.0597641 0.00220837 -0.00673475 -0.999492 0.031067 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -5.09769e-05 0.00884522 3.99988 -0.0274223 0.00406838 +EDGE_SE3:QUAT 1548 1549 4.57877 -0.0737712 0.0266616 -0.000960285 -0.00157138 0.00636108 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.36218e-06 -0.012497 3.99999 -3.97262e-05 3.99988 +EDGE_SE3:QUAT 892 1548 2.14642 4.61938 -0.0111193 0.00733563 0.00955974 0.952599 0.303989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 9.84733e-05 -0.030976 3.99966 -0.0458859 0.370457 +EDGE_SE3:QUAT 893 1548 -4.85367 4.06235 -0.0181922 -0.00117015 0.0107907 0.999215 0.0380918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -8.33289e-05 0.00469669 3.99958 -0.0426485 0.00626492 +EDGE_SE3:QUAT 1549 1550 4.56878 -0.0646662 0.0244201 0.00342051 0.00202431 0.010448 0.999938 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.76991e-05 0.015763 3.99998 8.19202e-05 3.99963 +EDGE_SE3:QUAT 892 1549 -1.51651 7.31152 0.0561388 0.0085866 0.0081914 0.954531 0.297874 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 0.0002625 -0.0368805 3.99994 -0.0443765 0.355798 +EDGE_SE3:QUAT 1550 1551 4.41578 -0.0240363 -0.00169701 -0.00494354 -0.00293141 0.0121908 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 5.79636e-05 -0.0227227 3.99997 -0.000138005 3.99953 +EDGE_SE3:QUAT 1551 1552 4.64317 -0.0434379 0.0163675 0.00252398 -0.00219123 0.0138773 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.11636e-05 -0.0179452 3.99998 -0.000125181 3.99931 +EDGE_SE3:QUAT 1552 1553 4.24389 -0.0308618 -0.000399642 0.000888822 0.0107143 0.01482 0.999832 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00183 7.87626e-05 0.0855622 3.99954 0.00063676 4.00095 +EDGE_SE3:QUAT 1553 1554 4.46554 -0.033708 0.00845222 0.00176977 -0.00352614 0.0146634 0.999885 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00019 -2.08732e-05 -0.0285125 3.99995 -0.000209274 3.99934 +EDGE_SE3:QUAT 1554 1555 4.37216 -0.0258654 0.0140848 0.00156866 -0.00075432 0.0147952 0.999889 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.80553e-06 -0.00631103 4 -4.73456e-05 3.99913 +EDGE_SE3:QUAT 1555 1556 4.50663 -0.0365507 0.0151342 0.00086506 0.000428416 0.0146532 0.999892 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 1.45421e-06 0.00327413 4 2.36177e-05 3.99914 +EDGE_SE3:QUAT 1556 1557 4.44013 -0.0282924 0.0121622 0.000528064 -0.00191541 0.0146782 0.99989 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00006 -2.77288e-06 -0.0154116 3.99999 -0.00011328 3.9992 +EDGE_SE3:QUAT 1557 1558 4.38386 -0.024101 0.0143407 -6.59036e-05 0.00398159 0.0138302 0.999896 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 4.21348e-06 0.0318563 3.99994 0.000220305 3.99949 +EDGE_SE3:QUAT 1558 1559 4.29072 -0.0401218 0.0143239 0.000292497 -0.00253879 0.0136089 0.999904 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 -8.66598e-07 -0.0203529 3.99997 -0.00013855 3.99936 +EDGE_SE3:QUAT 1559 1560 4.28518 -0.0513077 0.00932354 0.00193587 0.00281734 0.0129706 0.99991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 2.38411e-05 0.0222322 3.99997 0.000143892 3.99945 +EDGE_SE3:QUAT 1560 1561 4.18272 -0.032442 0.00875181 -0.00129177 0.00147131 0.0130508 0.999913 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -7.07815e-06 0.0119698 3.99999 7.84746e-05 3.99935 +EDGE_SE3:QUAT 1561 1562 4.21955 -0.0440722 0.0165726 -0.00137433 0.000154837 0.0128686 0.999916 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -1.03583e-06 0.00145059 4 9.78698e-06 3.99934 +EDGE_SE3:QUAT 1562 1563 4.26047 -0.0453943 0.0160343 0.000577694 -0.000724117 0.0134741 0.999909 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -1.53486e-06 -0.00588476 4 -3.98448e-05 3.99928 +EDGE_SE3:QUAT 1563 1564 4.13057 -0.0526471 0.0147843 0.00214587 0.00107787 0.0132342 0.99991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 9.10778e-06 0.00827992 4 5.40889e-05 3.99932 +EDGE_SE3:QUAT 1564 1565 4.09789 -0.0495363 0.0158039 0.00279549 0.00206674 0.0134554 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 2.35826e-05 0.0160782 3.99998 0.000107426 3.99934 +EDGE_SE3:QUAT 1565 1566 4.0041 -0.0464073 0.0101666 0.00135679 0.00111674 0.0139698 0.999901 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 6.25431e-06 0.00870389 4 6.02999e-05 3.99924 +EDGE_SE3:QUAT 1566 1567 4.03631 -0.0435585 0.0141006 9.29652e-05 -0.00130488 0.0152681 0.999883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 1.3918e-07 -0.0104525 3.99999 -7.98265e-05 3.99909 +EDGE_SE3:QUAT 1567 1568 4.96747 -0.0128106 0.0130341 -0.00371345 0.000286066 0.0202764 0.999787 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -6.41404e-06 0.00319036 4 3.53807e-05 3.99836 +EDGE_SE3:QUAT 1568 1569 5.04548 -0.0214435 0.0121703 0.00136121 -0.000594008 0.017587 0.999844 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.32977e-06 -0.00503707 4 -4.51164e-05 3.99877 +EDGE_SE3:QUAT 1569 1570 4.70074 -0.0339154 0.0221262 -0.00136739 0.00223151 0.0140213 0.999898 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00007 -1.07023e-05 0.0180771 3.99998 0.000127098 3.9993 +EDGE_SE3:QUAT 1570 1571 4.68005 -0.0570408 0.0265055 0.000671142 0.00258529 0.0115213 0.99993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 8.73251e-06 0.0205859 3.99997 0.000118517 3.99957 +EDGE_SE3:QUAT 1571 1572 4.48726 -0.0524591 0.0288692 0.000230707 0.000246068 0.0139565 0.999903 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.40708e-07 0.00192934 4 1.33726e-05 3.99922 +EDGE_SE3:QUAT 1572 1573 4.35998 -0.0381347 0.0374068 0.00109664 0.00917881 0.0163271 0.999824 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00133 7.29927e-05 0.0732075 3.99967 0.000599703 4.00027 +EDGE_SE3:QUAT 1573 1574 4.72003 0.00914643 0.0333544 -0.00887613 -0.011448 0.0180232 0.999733 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00169 0.000450324 -0.0896482 3.99951 -0.000830034 4.00071 +EDGE_SE3:QUAT 1574 1575 4.47025 -0.0233192 0.0420408 0.00329202 0.00742764 0.0181758 0.999802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00082 0.000119846 0.0586838 3.99979 0.000535624 3.99954 +EDGE_SE3:QUAT 1575 1576 4.13867 -0.0453317 0.0371163 0.00294225 -0.000902456 0.0158642 0.999869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.13657e-05 -0.00777688 4 -6.30966e-05 3.99901 +EDGE_SE3:QUAT 1576 1577 4.41695 -0.0422906 0.035542 -0.00276451 0.00335565 0.0105306 0.999935 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00015 -3.48446e-05 0.0271909 3.99995 0.000143028 3.99974 +EDGE_SE3:QUAT 1577 1578 4.08216 -0.060044 0.0361653 -0.00285943 0.000923982 0.00975026 0.999948 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.09899e-05 0.00772528 4 3.81412e-05 3.99963 +EDGE_SE3:QUAT 1578 1579 4.09339 -0.0364571 0.0235707 -0.00319292 -0.0127595 0.0116762 0.999845 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00254 0.000207663 -0.101663 3.99936 -0.000606012 4.00204 +EDGE_SE3:QUAT 1579 1580 4.35207 -0.000482339 -0.029058 0.0017158 0.00414306 0.0402872 0.999178 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 4.33101e-05 0.0322369 3.99994 0.000644044 3.99377 +EDGE_SE3:QUAT 1580 1581 4.22607 0.321979 -0.00125198 -0.00248052 -0.00136112 0.110114 0.993915 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 1.05785e-05 -0.00744026 4 -0.00034589 3.95151 +EDGE_SE3:QUAT 1581 1582 4.29332 0.452132 -0.0191827 -0.00345563 0.00103885 0.127476 0.991835 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -1.87766e-05 0.0133379 3.99999 0.00095789 3.93504 +EDGE_SE3:QUAT 1582 1583 4.12548 0.426787 -0.0321306 0.00354605 -0.00300403 0.124186 0.992248 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -1.77556e-05 -0.0287095 3.99995 -0.00187956 3.93852 +EDGE_SE3:QUAT 1583 1584 4.40897 0.501188 -0.0124451 0.00533112 0.0116407 0.132863 0.991052 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00157 0.0005702 0.0822939 3.99965 0.00524462 3.93108 +EDGE_SE3:QUAT 1584 1585 4.12925 0.393631 -0.00911248 0.00166248 0.00398279 0.115318 0.993319 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0002 6.13692e-05 0.0289498 3.99995 0.00161346 3.94702 +EDGE_SE3:QUAT 1585 1586 4.40671 0.347387 0.0133571 0.00257511 0.0139608 0.0970795 0.995175 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00284 0.000564389 0.107194 3.99933 0.00515048 3.96517 +EDGE_SE3:QUAT 1586 1587 4.65762 0.234911 0.0491921 -0.000920582 -0.0130923 0.0551104 0.998394 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00268 0.000271252 -0.103714 3.99934 -0.00285672 3.99054 +EDGE_SE3:QUAT 1587 1588 4.23679 -0.0730747 -0.0109784 0.00411342 -0.000301456 0.00583101 0.999974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -5.73365e-06 -0.00269928 4 -8.1386e-06 3.99987 +EDGE_SE3:QUAT 1588 1589 4.21832 -0.0889675 0.0170931 -0.00175259 0.00132717 1.40141e-05 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -9.30386e-06 0.0106176 3.99999 3.09559e-10 4.00003 +EDGE_SE3:QUAT 1589 1590 4.27833 -0.0988 0.0107317 3.23431e-06 -0.00286132 0.000642361 0.999996 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 8.9202e-08 -0.0228912 3.99997 -7.35222e-06 4.00013 +EDGE_SE3:QUAT 1590 1591 4.40998 -0.0949855 0.00549966 -0.000153308 -4.58852e-05 0.00183494 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.78844e-08 -0.000363704 4 -3.32662e-07 3.99999 +EDGE_SE3:QUAT 1591 1592 4.54334 -0.0996723 0.0105817 0.00247188 0.00169895 0.00282296 0.999992 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.68543e-05 0.0135077 3.99999 1.91966e-05 4.00001 +EDGE_SE3:QUAT 1592 1593 4.03854 -0.0750455 0.0151473 0.00130705 0.000469692 0.00397286 0.999991 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.42176e-06 0.00369513 4 7.30555e-06 3.99994 +EDGE_SE3:QUAT 1593 1594 4.44764 -0.0759775 -0.00121651 -0.0029518 -0.000275668 0.00395956 0.999988 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 2.98524e-06 -0.00206501 4 -4.00053e-06 3.99994 +EDGE_SE3:QUAT 1594 1595 4.89109 -0.085759 0.002902 -0.000179394 -0.000511224 0.00185881 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 3.78005e-07 -0.00408578 4 -3.79723e-06 3.99999 +EDGE_SE3:QUAT 1595 1596 4.95675 -0.0894486 0.0145748 -0.00238454 0.00260826 0.000700614 0.999994 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -2.47974e-05 0.0208865 3.99997 6.9296e-06 4.00011 +EDGE_SE3:QUAT 1596 1597 4.03754 -0.103702 0.0171322 0.000359865 -0.000604949 -6.70798e-05 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -8.71324e-07 -0.00483931 4 1.65467e-07 4.00001 +EDGE_SE3:QUAT 1597 1598 5.00217 -0.113827 0.0167112 0.000959698 0.0014692 0.00045836 0.999998 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 5.66047e-06 0.0117484 3.99999 2.74184e-06 4.00003 +EDGE_SE3:QUAT 1598 1599 4.97894 -0.120363 0.0209915 -0.000316389 -0.000651806 -0.000312717 1 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 8.21963e-07 -0.00521564 4 8.12348e-07 4.00001 +EDGE_SE3:QUAT 1599 1600 5.12511 -0.128454 0.0261588 0.00350091 0.000240649 -0.00113808 0.999993 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 3.47982e-06 0.00197296 4 -1.1267e-06 4 +EDGE_SE3:QUAT 1600 1601 4.91992 -0.128263 0.0243036 -0.00150868 -0.00157271 -0.00104487 0.999997 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 9.44798e-06 -0.0126006 3.99999 6.49672e-06 4.00004 +EDGE_SE3:QUAT 1601 1602 4.95072 -0.127683 0.0211913 -0.000279126 0.000602345 -0.000752746 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -6.78604e-07 0.00481624 4 -1.81482e-06 4 +EDGE_SE3:QUAT 1602 1603 4.90559 -0.110356 0.0158775 0.000974569 -0.000181719 -0.000997198 0.999999 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.0159e-07 -0.00144208 4 7.17845e-07 4 +EDGE_SE3:QUAT 1603 1604 4.92211 -0.146581 0.0342474 0.00386419 -0.00572578 -0.00513414 0.999963 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00046 -9.19288e-05 -0.0455705 3.99987 0.000119833 4.00041 +EDGE_SE3:QUAT 1604 1605 4.84917 -0.127158 0.00471935 -0.00599569 -0.000287833 -0.00643405 0.999961 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 8.73515e-06 -0.00276529 4 9.3762e-06 3.99984 +EDGE_SE3:QUAT 1605 1606 4.66468 -0.13583 0.0327671 -0.00199417 0.0011833 -0.00533841 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -9.44418e-06 0.00933823 3.99999 -2.48776e-05 3.99991 +EDGE_SE3:QUAT 1606 1607 4.85398 -0.144049 0.0273182 0.00162506 -0.00107992 -0.004628 0.999987 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -7.0492e-06 -0.00854886 4 1.97572e-05 3.99993 +EDGE_SE3:QUAT 1607 1608 4.49636 -0.117259 0.0207594 -0.00426188 -0.000604383 -0.0050494 0.999978 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 1.09881e-05 -0.00509299 4 1.30348e-05 3.9999 +EDGE_SE3:QUAT 1608 1609 4.6889 -0.173549 0.00208799 0.00725482 -0.000179307 -0.00898126 0.999933 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -1.42286e-06 -0.000652353 4 1.76049e-06 3.99968 +EDGE_SE3:QUAT 1609 1610 4.43355 -0.163263 0.025863 -0.000740686 -2.30565e-06 -0.0128757 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 6.32796e-08 -0.000132871 4 1.10098e-06 3.99934 +EDGE_SE3:QUAT 1610 1611 4.327 -0.156474 0.026917 -0.00218966 0.00104309 -0.0125996 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -8.95891e-06 0.0080117 4 -4.98268e-05 3.99938 +EDGE_SE3:QUAT 1611 1612 4.37833 -0.145636 0.0201934 -0.000721739 0.000332608 -0.0116195 0.999932 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.406e-07 0.0025597 4 -1.46771e-05 3.99946 +EDGE_SE3:QUAT 1612 1613 4.32384 -0.171139 0.00388387 -0.000254011 -0.00162312 -0.0155488 0.999878 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00004 6.6816e-07 -0.0130277 3.99999 0.00010138 3.99908 +EDGE_SE3:QUAT 1613 1614 4.30798 -0.168415 0.00572135 -0.000858778 0.00107139 -0.0152984 0.999882 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -3.99774e-06 0.00841053 4 -6.39479e-05 3.99908 +EDGE_SE3:QUAT 1614 1615 4.29487 -0.162255 0.0136193 -0.00167982 0.00096719 -0.0151582 0.999883 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.47333e-06 0.00742934 4 -5.55648e-05 3.99909 +EDGE_SE3:QUAT 42 1614 4.87428 4.49879 -0.0768914 0.00398712 -0.0167261 -0.998233 0.0568859 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000148978 0.016006 3.99898 -0.0681652 0.0141738 +EDGE_SE3:QUAT 43 1614 -0.893906 5.11172 -0.072377 0.00911984 -0.0153948 -0.97501 0.221441 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 -0.000216035 0.0377363 3.99919 -0.0695206 0.197771 +EDGE_SE3:QUAT 1615 1616 4.35773 -0.157655 0.0171106 -0.00055747 -0.000835903 -0.0128005 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.6763e-06 -0.00677121 4 4.35073e-05 3.99936 +EDGE_SE3:QUAT 41 1615 4.89907 4.00687 -0.0217422 0.00867054 -0.0138869 -0.999755 0.0148752 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99973 -0.0004841 0.0347027 4.00035 -0.0565649 0.00198612 +EDGE_SE3:QUAT 42 1615 0.618341 4.16465 -0.097643 0.00521194 -0.0150533 -0.999005 0.0416491 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000257215 0.0208997 3.99938 -0.0616854 0.00800093 +EDGE_SE3:QUAT 43 1615 -4.81208 3.427 -0.115932 0.00967444 -0.0135045 -0.978377 0.206162 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000365351 0.0401517 3.99963 -0.0636455 0.171473 +EDGE_SE3:QUAT 1616 1617 4.37141 -0.181371 0.00556954 0.0011889 0.000154122 -0.0177595 0.999842 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.19659e-07 0.00148571 4 -1.394e-05 3.99874 +EDGE_SE3:QUAT 40 1616 4.64878 4.01411 -0.0965022 0.0114208 -0.02093 -0.999663 0.0102623 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99952 -0.000951489 0.0457181 4.00022 -0.0846749 0.002736 +EDGE_SE3:QUAT 41 1616 0.545643 4.0332 -0.0900535 0.00805075 -0.0131569 -0.999879 0.00212537 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99974 -0.000424257 0.0322106 4.00033 -0.052778 0.000973702 +EDGE_SE3:QUAT 42 1616 -3.72873 3.95758 -0.121512 0.00485553 -0.0142291 -0.99947 0.0288802 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000242339 0.0194492 3.99948 -0.0579185 0.00427031 +EDGE_SE3:QUAT 1617 1618 4.32815 -0.182213 -0.000356666 0.000280566 0.000980957 -0.0183688 0.999831 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 6.82557e-07 0.00790554 4 -7.27791e-05 3.99867 +EDGE_SE3:QUAT 39 1617 4.57812 4.07906 -0.0591696 0.00518899 -0.014004 -0.999825 0.0112941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000279644 0.0207656 3.99961 -0.0564692 0.00141537 +EDGE_SE3:QUAT 40 1617 0.309183 4.09873 -0.187013 -0.0120349 0.0218739 0.99966 0.00754972 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99939 -0.00105593 0.048174 4.0005 -0.0868072 0.00269149 +EDGE_SE3:QUAT 41 1617 -3.76578 4.18617 -0.145561 -0.00901473 0.013636 0.999741 0.0158131 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 -0.000482826 0.0360806 4.00065 -0.0533901 0.00203836 +EDGE_SE3:QUAT 1618 1619 4.39043 -0.193119 0.0129997 0.00229804 -0.000963477 -0.0161868 0.999866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -8.4967e-06 -0.00725845 4 5.75801e-05 3.99897 +EDGE_SE3:QUAT 38 1618 4.33161 4.12781 -0.110821 0.0069288 -0.0188869 -0.999735 0.0112014 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000503297 0.0277344 3.99927 -0.0761498 0.00214423 +EDGE_SE3:QUAT 39 1618 0.26143 4.14553 -0.105766 -0.00666454 0.0142301 0.999853 0.00680135 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.00038293 0.0266674 3.99993 -0.0565599 0.00116257 +EDGE_SE3:QUAT 40 1618 -4.006 4.34775 -0.3119 -0.0138028 0.021973 0.999341 0.0253855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99912 -0.00118503 0.0552973 4.00149 -0.0850265 0.00515005 +EDGE_SE3:QUAT 1619 1620 4.33949 -0.180779 0.0103998 0.000744134 -0.00108841 -0.015782 0.999875 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -3.60551e-06 -0.00856319 4 6.72141e-05 3.99902 +EDGE_SE3:QUAT 37 1619 4.50169 4.2037 -0.1374 0.00633474 -0.0228549 -0.999625 0.0136539 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -0.000533194 0.0253643 3.99846 -0.0920624 0.00302651 +EDGE_SE3:QUAT 38 1619 -0.0246381 4.2207 -0.157553 -0.00619671 0.021714 0.999731 0.00534181 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 -0.000553001 0.0248051 3.99876 -0.0865837 0.00214264 +EDGE_SE3:QUAT 39 1619 -4.09231 4.39269 -0.149315 -0.0058858 0.0168775 0.999583 0.0226657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99982 -0.000426808 0.0235725 3.99953 -0.066362 0.00329554 +EDGE_SE3:QUAT 1620 1621 4.40341 -0.161375 -0.00106608 -0.000686433 0.00243367 -0.0135757 0.999905 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -8.54103e-06 0.0193525 3.99998 -0.000131202 3.99936 +EDGE_SE3:QUAT 36 1620 4.26499 4.22992 -0.162218 0.00112251 -0.0254722 -0.999575 0.0141218 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.10723e-05 0.0044933 3.99741 -0.101932 0.00340247 +EDGE_SE3:QUAT 37 1620 0.159588 4.26133 -0.17609 -0.00611091 0.0230124 0.999714 0.00200238 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000568866 0.0244628 3.99849 -0.0919459 0.00227981 +EDGE_SE3:QUAT 38 1620 -4.36221 4.45267 -0.21078 -0.00596512 0.0223029 0.999517 0.0207968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000593145 0.0238956 3.99872 -0.0881223 0.00381556 +EDGE_SE3:QUAT 1621 1622 4.47461 -0.135161 0.0130137 -0.00520227 0.000554146 -0.0126662 0.999906 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -8.85408e-06 0.00364131 4 -2.14174e-05 3.99936 +EDGE_SE3:QUAT 35 1621 4.02869 4.21071 -0.0994682 0.00473176 -0.0207495 -0.999643 0.0161654 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -0.000343914 0.018945 3.99856 -0.0835461 0.00288104 +EDGE_SE3:QUAT 36 1621 -0.140154 4.2638 -0.157934 0.00398114 -0.0244672 -0.999692 0.000759126 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.000385898 0.0159387 3.99786 -0.097872 0.00246176 +EDGE_SE3:QUAT 37 1621 -4.20099 4.43899 -0.230711 -0.00924551 0.0224025 0.999592 0.0151247 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000855413 0.037021 3.99951 -0.0884639 0.00321459 +EDGE_SE3:QUAT 1622 1623 4.42625 -0.153182 0.00238998 -0.00395688 0.0039779 -0.0115424 0.999918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00018 -6.57752e-05 0.0312698 3.99994 -0.000180887 3.99971 +EDGE_SE3:QUAT 34 1622 3.97008 4.14631 -0.0830815 0.00231109 -0.012625 -0.999745 0.0185624 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.47814e-05 0.00925043 3.99942 -0.0507964 0.00204503 +EDGE_SE3:QUAT 35 1622 -0.42403 4.21211 -0.136992 0.00559565 -0.0152329 -0.999861 0.00373134 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000336739 0.0223905 3.99956 -0.0610996 0.00111438 +EDGE_SE3:QUAT 36 1622 -4.57278 4.40737 -0.197074 -0.00493041 0.0191277 0.999737 0.0116821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000403638 0.0197368 3.99898 -0.0760215 0.00208859 +EDGE_SE3:QUAT 1623 1624 4.41978 -0.12604 -9.52053e-05 0.00043646 0.00266504 -0.00642925 0.999976 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 3.56403e-06 0.0213532 3.99997 -6.86076e-05 3.99995 +EDGE_SE3:QUAT 33 1623 4.01691 4.07918 -0.0832389 0.00389056 -0.0102129 -0.999706 0.0216456 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000147571 0.0155747 3.99978 -0.0414779 0.00236511 +EDGE_SE3:QUAT 34 1623 -0.442365 4.13618 -0.0968128 0.00660838 -0.00910391 -0.999911 0.00718093 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000243317 0.0264384 4.00035 -0.0367977 0.000719502 +EDGE_SE3:QUAT 35 1623 -4.81692 4.3294 -0.185449 -0.00992179 0.011962 0.999851 0.00755937 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 -0.000465633 0.0396967 4.00105 -0.0472639 0.00118084 +EDGE_SE3:QUAT 1624 1625 4.52037 -0.160043 6.41136e-05 0.00460013 -0.00399406 -0.00856891 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00016 -7.52495e-05 -0.0314767 3.99994 0.000135921 3.99995 +EDGE_SE3:QUAT 32 1624 4.15355 3.95547 -0.0827699 0.00406057 -0.00963641 -0.999486 0.0303033 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.00014377 0.0162647 3.99984 -0.0394417 0.00412861 +EDGE_SE3:QUAT 33 1624 -0.417085 4.01607 -0.118272 0.00685919 -0.0111198 -0.999797 0.0153193 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 -0.000306205 0.0274509 4.0002 -0.0453016 0.00164027 +EDGE_SE3:QUAT 34 1624 -4.84592 4.20068 -0.165744 0.00986567 -0.00972255 -0.999903 0.00125027 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 -0.000386092 0.0394665 4.00117 -0.0390077 0.000775908 +EDGE_SE3:QUAT 1625 1626 4.3784 -0.167214 -0.00683481 0.00037961 0.00570054 -0.0152656 0.999867 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00052 -3.25738e-06 0.0456631 3.99987 -0.000348497 3.99959 +EDGE_SE3:QUAT 31 1625 4.4699 3.78458 -0.0929384 -0.000457551 -0.0156683 -0.999324 0.0332514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 9.29616e-05 -0.00183951 3.99904 -0.0623711 0.00539733 +EDGE_SE3:QUAT 32 1625 -0.372033 3.83084 -0.114816 0.000592819 -0.0146413 -0.999655 0.0218182 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.70961e-06 0.00237197 3.99914 -0.0585925 0.00276442 +EDGE_SE3:QUAT 33 1625 -4.91932 4.03013 -0.17726 0.00364203 -0.0157048 -0.99984 0.00771486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000215734 0.0145745 3.9992 -0.0630309 0.00128464 +EDGE_SE3:QUAT 1626 1627 4.50868 -0.196405 0.0143591 0.0012235 0.00251997 -0.0171471 0.999849 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0001 9.86897e-06 0.020403 3.99997 -0.000175442 3.99893 +EDGE_SE3:QUAT 30 1626 4.70904 3.61017 -0.0735356 0.00262878 -0.0169474 -0.999363 0.0313059 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000108893 0.0105298 3.9989 -0.0682727 0.00511471 +EDGE_SE3:QUAT 31 1626 0.0604157 3.63892 -0.0984239 0.00577017 -0.0159032 -0.999688 0.018385 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000342566 0.0230999 3.99944 -0.0644095 0.00252305 +EDGE_SE3:QUAT 32 1626 -4.7376 3.81113 -0.133284 0.00716511 -0.0146797 -0.999844 0.0067863 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000417184 0.0286711 3.99992 -0.0591106 0.00126323 +EDGE_SE3:QUAT 1627 1628 4.45958 -0.151169 0.0284431 0.000454493 -0.00290508 -0.012576 0.999917 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 -7.79444e-06 -0.0231672 3.99997 0.000145625 3.9995 +EDGE_SE3:QUAT 29 1627 5.02069 3.48312 -0.0702481 0.00487028 -0.0179908 -0.99932 0.0318275 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000280702 0.0195145 3.99896 -0.0730148 0.00548166 +EDGE_SE3:QUAT 30 1627 0.235959 3.50847 -0.0917453 0.0055329 -0.0186236 -0.99971 0.0142447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000381667 0.0221488 3.99903 -0.0750852 0.0023443 +EDGE_SE3:QUAT 31 1627 -4.42386 3.65647 -0.129863 0.00885966 -0.0170705 -0.999814 0.0014601 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99969 -0.000604588 0.0354529 4.00008 -0.0684047 0.00149238 +EDGE_SE3:QUAT 1628 1629 4.45962 -0.174245 0.0101186 0.000265351 0.00261902 -0.0176246 0.999841 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -1.23632e-07 0.020999 3.99997 -0.000185155 3.99887 +EDGE_SE3:QUAT 28 1628 5.4824 3.38149 -0.10629 -0.000835532 -0.0219736 -0.999054 0.0375298 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 0.000215111 -0.00336393 3.99813 -0.0873152 0.00754637 +EDGE_SE3:QUAT 29 1628 0.653529 3.35382 -0.0814387 0.00260426 -0.0182239 -0.999653 0.0188657 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000141674 0.010426 3.99874 -0.0732135 0.00279178 +EDGE_SE3:QUAT 30 1628 -4.19504 3.52176 -0.120706 0.0033596 -0.0190941 -0.99981 0.00212253 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000250813 0.0134457 3.99872 -0.0764234 0.00152379 +EDGE_SE3:QUAT 1629 1630 4.5905 -0.201537 0.0181564 0.000185858 0.00118931 -0.0217508 0.999763 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 1.4576e-07 0.00955626 3.99999 -0.000104075 3.99813 +EDGE_SE3:QUAT 27 1629 5.05843 3.20195 -0.0818437 0.00211504 -0.0223989 -0.999093 0.036165 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.49556e-05 0.00847143 3.998 -0.0898915 0.00727334 +EDGE_SE3:QUAT 28 1629 1.04756 3.21267 -0.0753229 0.00253279 -0.0218671 -0.999549 0.0204393 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000144977 0.0101417 3.99814 -0.0877717 0.00362442 +EDGE_SE3:QUAT 29 1629 -3.84079 3.35759 -0.093143 0.00585379 -0.0183145 -0.999814 0.00148428 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -0.000425973 0.0234266 3.9992 -0.0733283 0.00149046 +EDGE_SE3:QUAT 1630 1631 4.22449 -0.221751 0.0253988 9.36988e-05 -0.000355006 -0.0283852 0.999597 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.15085e-07 -0.00280472 4 3.96394e-05 3.99678 +EDGE_SE3:QUAT 26 1630 5.22014 3.04022 -0.0965048 0.00187456 -0.0225273 -0.999341 0.0283974 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.4116e-05 0.00750633 3.99798 -0.0903307 0.00528232 +EDGE_SE3:QUAT 27 1630 0.472891 3.06939 -0.0883051 0.0038669 -0.0220953 -0.999648 0.0141986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 -0.000290076 0.015482 3.99823 -0.0887598 0.00283713 +EDGE_SE3:QUAT 28 1630 -3.51972 3.21772 -0.0906732 -0.00439837 0.0218303 0.999751 0.00115259 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 -0.000387661 0.017606 3.99841 -0.0872688 0.00198746 +EDGE_SE3:QUAT 1631 1632 4.35221 -0.213366 0.0227815 -0.00254701 -0.00145924 -0.0233938 0.999722 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.47538e-05 -0.0123791 3.99999 0.000147408 3.99785 +EDGE_SE3:QUAT 25 1631 5.66212 3.00296 -0.0941246 0.00142744 -0.0231075 -0.999631 0.0141866 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -7.15379e-05 0.00571416 3.99788 -0.0925213 0.00295481 +EDGE_SE3:QUAT 26 1631 0.989998 3.00551 -0.094247 0.00198482 -0.0226552 -0.999741 0.000501486 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000177679 0.00794533 3.99801 -0.0906073 0.00207022 +EDGE_SE3:QUAT 27 1631 -3.77402 3.17326 -0.0870579 -0.00456909 0.021759 0.999658 0.0137581 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000441412 0.0182955 3.99851 -0.0864833 0.00271165 +EDGE_SE3:QUAT 1632 1633 4.29661 -0.151941 0.00800613 0.00053275 0.000751799 -0.0108589 0.999941 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00001 1.47645e-06 0.00608276 4 -3.31427e-05 3.99954 +EDGE_SE3:QUAT 24 1632 5.65616 3.07285 -0.0591334 0.000778299 -0.0163638 -0.999841 0.00699447 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.60003e-05 0.00311439 3.99893 -0.0654822 0.00127043 +EDGE_SE3:QUAT 25 1632 1.30964 3.07219 -0.0908219 -0.000377126 0.0205289 0.999749 0.00896583 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -6.10824e-05 0.00151038 3.99832 -0.0820548 0.0020062 +EDGE_SE3:QUAT 26 1632 -3.31654 3.20796 -0.0987268 -0.00145368 0.0200154 0.999539 0.0227779 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000186998 0.00582596 3.99847 -0.0796788 0.00367243 +EDGE_SE3:QUAT 1633 1634 4.35631 -0.129577 0.0161601 0.00166563 0.00275973 -0.00631414 0.999975 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 1.7363e-05 0.0222032 3.99997 -6.99269e-05 3.99996 +EDGE_SE3:QUAT 23 1633 5.83881 3.18765 -0.0666695 5.20104e-05 -0.0157196 -0.999778 0.0140118 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 2.4412e-05 0.000207399 3.99901 -0.0628457 0.00177316 +EDGE_SE3:QUAT 24 1633 1.37975 3.17194 -0.0645848 -0.00170092 0.0169627 0.999847 0.0038057 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -0.000123815 0.0068069 3.9989 -0.0677878 0.00121864 +EDGE_SE3:QUAT 25 1633 -2.9449 3.30236 -0.0930233 -0.00123766 0.0211418 0.999581 0.0197406 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.00017365 0.00495957 3.99827 -0.0842719 0.00334181 +EDGE_SE3:QUAT 1634 1635 4.20828 -0.106098 0.0169031 0.00163221 -0.00160926 -0.00557198 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00003 -1.07292e-05 -0.0127644 3.99999 3.55605e-05 3.99992 +EDGE_SE3:QUAT 22 1634 5.65993 3.23238 -0.0673591 0.00307226 -0.0208696 -0.999468 0.0248698 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000172953 0.0123042 3.99834 -0.0839444 0.00427535 +EDGE_SE3:QUAT 23 1634 1.51098 3.19486 -0.0478791 0.00321024 -0.0176165 -0.999808 0.0078958 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000208232 0.0128477 3.9989 -0.0706505 0.00153891 +EDGE_SE3:QUAT 24 1634 -2.96107 3.33633 -0.0688464 -0.00512099 0.0190654 0.999758 0.00973518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000411993 0.0204981 3.99901 -0.075843 0.00192261 +EDGE_SE3:QUAT 1635 1636 4.18615 -0.0845266 0.0254468 -0.00464139 0.00333776 -0.0055518 0.999968 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00009 -6.24713e-05 0.0263918 3.99996 -7.42e-05 4.00005 +EDGE_SE3:QUAT 21 1635 5.45777 3.13298 -0.119215 -0.00466546 -0.0250908 -0.999255 0.0289373 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 0.000591697 -0.0187098 3.99801 -0.09906 0.00589348 +EDGE_SE3:QUAT 22 1635 1.47332 3.14236 -0.0683572 0.00186867 -0.0224983 -0.999564 0.0190429 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -9.16522e-05 0.0074815 3.998 -0.090174 0.00349911 +EDGE_SE3:QUAT 23 1635 -2.71437 3.24405 -0.0523741 0.00203534 -0.0190119 -0.999814 0.00246306 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -0.000147788 0.00814571 3.99862 -0.0760746 0.00148819 +EDGE_SE3:QUAT 1636 1637 4.71497 -0.139613 0.0348208 0.00204922 -0.000116927 -0.0053658 0.999983 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -7.79512e-07 -0.000803425 4 2.038e-06 3.99988 +EDGE_SE3:QUAT 20 1636 5.87112 2.97636 -0.0223156 0.00604351 -0.0178198 -0.999239 0.0341708 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000366148 0.0242213 3.99915 -0.0727208 0.00614117 +EDGE_SE3:QUAT 21 1636 1.30247 2.97948 -0.0434244 -0.000957881 -0.0200135 -0.999517 0.023738 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000151268 -0.00384066 3.99844 -0.0797445 0.00384897 +EDGE_SE3:QUAT 22 1636 -2.68922 3.06975 -0.0511209 0.00583159 -0.0177654 -0.999731 0.0136888 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000389701 0.0233431 3.99921 -0.0716676 0.00217025 +EDGE_SE3:QUAT 1637 1638 4.19205 -0.122098 0.0268189 0.00301926 0.00184332 -0.00540729 0.999979 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 2.22054e-05 0.0149418 3.99999 -4.03232e-05 3.99994 +EDGE_SE3:QUAT 19 1637 5.32486 2.77309 -0.0627117 0.00217966 -0.0195954 -0.998907 0.0423839 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -4.15081e-05 0.00873269 3.99848 -0.0787529 0.00875853 +EDGE_SE3:QUAT 20 1637 1.1494 2.79004 -0.0391009 0.00633578 -0.0200075 -0.999377 0.0283749 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 -0.000437075 0.0253841 3.99888 -0.0813034 0.00503597 +EDGE_SE3:QUAT 21 1637 -3.40104 2.90652 -0.00195276 -0.000789879 -0.0228116 -0.99958 0.017873 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 0.000145644 -0.00316619 3.99795 -0.0910378 0.00335398 +EDGE_SE3:QUAT 1638 1639 4.03208 -0.140343 0.0352138 -0.00174759 0.000223705 -0.0242364 0.999705 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 -9.8757e-07 0.00127999 4 -1.3453e-05 3.99765 +EDGE_SE3:QUAT 18 1638 5.27338 2.73593 -0.0364283 0.0068588 -0.0192965 -0.996922 0.0756817 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -0.0003458 0.027616 3.99884 -0.0802067 0.0247198 +EDGE_SE3:QUAT 19 1638 1.13481 2.53469 -0.0416504 0.00445244 -0.0226127 -0.999065 0.036566 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.000262459 0.0178474 3.99812 -0.0914314 0.00752162 +EDGE_SE3:QUAT 20 1638 -3.032 2.65721 -0.0606195 0.00835259 -0.0230861 -0.999432 0.0230754 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99979 -0.00070495 0.0334602 3.99878 -0.0937677 0.00460957 +EDGE_SE3:QUAT 1639 1640 4.26433 -0.485648 0.0221284 -7.93151e-05 0.00127944 -0.120986 0.992653 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00002 -4.93281e-06 0.00989763 3.99999 -0.000591849 3.94147 +EDGE_SE3:QUAT 17 1639 4.95508 2.83287 -0.0288672 0.00474301 -0.00451255 -0.986962 0.160821 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 -0.00011067 0.0195446 4.00011 -0.0228396 0.103684 +EDGE_SE3:QUAT 18 1639 1.28178 2.25424 -0.0505188 0.00750178 -0.0169003 -0.998508 0.0513855 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -0.000438753 0.0301199 3.99946 -0.0702365 0.0120257 +EDGE_SE3:QUAT 19 1639 -2.88914 2.37381 -0.0396139 0.00534216 -0.0204832 -0.999704 0.0119986 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.00040444 0.0213857 3.99872 -0.0824102 0.00238878 +EDGE_SE3:QUAT 1640 1641 4.20907 -0.9773 -0.0121778 -0.0196755 -0.0114269 -0.236021 0.971482 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00315 3.18928e-05 -0.137647 3.99875 0.0180342 3.78187 +EDGE_SE3:QUAT 16 1640 4.04242 2.69346 -0.0371051 -0.000777905 0.00585171 -0.977078 0.212801 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 3.81918e-05 -0.00286441 3.99988 0.0220633 0.181267 +EDGE_SE3:QUAT 17 1640 0.78026 1.91822 -0.0404276 0.00639995 -0.00394543 -0.999161 0.0402481 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 -0.000132915 0.0256604 4.00054 -0.0177789 0.00672364 +EDGE_SE3:QUAT 18 1640 -2.97561 2.27496 -0.0888216 -0.0110127 0.0161792 0.997379 0.0696627 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99932 -0.000600627 0.0444214 4.0015 -0.0578655 0.020749 +EDGE_SE3:QUAT 1641 1642 4.30548 -1.13435 -0.0153259 0.00730837 0.00797018 -0.2148 0.976598 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00129 -0.000157981 0.0776823 3.99964 -0.008845 3.81695 +EDGE_SE3:QUAT 14 1641 6.58383 3.22906 -0.0238646 -0.00466606 0.0158649 -0.94156 0.336439 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99984 0.000388046 -0.0167169 3.99908 0.057359 0.453782 +EDGE_SE3:QUAT 15 1641 3.21091 2.39907 0.0165386 0.00388882 0.0197618 -0.975198 0.220416 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99948 0.000548673 0.0183459 3.99996 0.0631018 0.195491 +EDGE_SE3:QUAT 16 1641 -0.210909 1.80966 -0.0359248 0.0172741 -0.0220003 0.999306 0.0246036 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99866 -0.00142995 -0.0691931 4.00329 0.0845987 0.00540729 +EDGE_SE3:QUAT 17 1641 -3.50413 2.54994 -0.101757 0.00503262 -0.0164003 0.98023 0.197116 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99956 -0.000373067 -0.0222766 4.00033 0.0517029 0.156256 +EDGE_SE3:QUAT 1642 1643 4.00108 -0.513873 -0.0106495 0.00110821 0.00260582 -0.0952538 0.995449 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00011 -4.47773e-06 0.0218231 3.99997 -0.00105483 3.96383 +EDGE_SE3:QUAT 13 1642 6.48533 1.52982 0.00715442 0.00184407 0.00441128 -0.988444 0.151514 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 3.01894e-05 0.00774869 4.00004 0.0144571 0.0918953 +EDGE_SE3:QUAT 14 1642 2.50938 1.37638 -0.01378 0.00186949 0.0102583 -0.991921 0.126431 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000145946 0.00782242 3.9998 0.0375424 0.0643143 +EDGE_SE3:QUAT 15 1642 -1.16701 1.5766 -0.027898 0.00895726 0.0145389 -0.999837 0.00582645 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 0.000519648 0.0358405 4.00047 0.057753 0.00129061 +EDGE_SE3:QUAT 16 1642 -4.42984 3.15486 0.148311 0.0138062 -0.0103182 0.970929 0.238748 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99907 0.000747232 -0.060851 4.00377 0.0106463 0.229025 +EDGE_SE3:QUAT 1643 1644 4.11446 -0.320664 -8.21395e-05 -0.00511068 0.000559438 -0.0669708 0.997742 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 2.59392e-06 0.000350404 4 3.44464e-05 3.98206 +EDGE_SE3:QUAT 12 1643 6.74219 1.32807 0.0177318 0.00417301 -0.000456552 -0.993291 0.115563 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -5.29582e-05 0.0170174 4.00026 -0.00557255 0.0535 +EDGE_SE3:QUAT 13 1643 2.52001 0.827486 -0.0126175 0.00427407 0.00392687 -0.998359 0.056971 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 4.57728e-05 0.0171851 4.00027 0.0136399 0.0131036 +EDGE_SE3:QUAT 14 1643 -1.46656 0.863543 -0.0258173 0.00380259 0.00991344 -0.999452 0.0313497 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000162108 0.0152373 3.9999 0.0386055 0.00436229 +EDGE_SE3:QUAT 15 1643 -5.14691 2.04531 -0.0854837 -0.0103297 -0.0143849 0.995742 0.0904661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99978 0.000601362 0.0417535 4.00026 0.0637995 0.0341999 +EDGE_SE3:QUAT 1644 1645 3.98079 -0.480287 -0.00196443 0.00295626 0.00539958 -0.106253 0.99432 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0005 -1.32974e-05 0.0462133 3.99987 -0.00250735 3.95537 +EDGE_SE3:QUAT 11 1644 6.47588 1.77966 0.00277929 0.00023739 0.00431194 -0.985209 0.171305 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99999 2.41661e-05 0.00116393 3.99995 0.0156797 0.117445 +EDGE_SE3:QUAT 12 1644 2.64467 0.720028 -0.0128682 0.00405762 0.0052798 -0.998782 0.0488826 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 7.39973e-05 0.0162938 4.0002 0.0194119 0.00971904 +EDGE_SE3:QUAT 13 1644 -1.59029 0.640093 -0.0411105 -0.00461882 -0.00921885 0.99989 0.0106187 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 0.000168251 0.0184805 3.99998 0.0372599 0.000883519 +EDGE_SE3:QUAT 14 1644 -5.57944 0.910414 -0.0511808 -0.00389358 -0.0151331 0.999226 0.036108 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 0.000178041 0.0156037 3.99923 0.0614548 0.00622163 +EDGE_SE3:QUAT 1645 1646 4.09062 -0.701715 0.000976882 3.60877e-05 0.000264421 -0.158177 0.987411 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -2.28608e-07 0.00210383 4 -0.000166062 3.89992 +EDGE_SE3:QUAT 10 1645 6.52799 2.03487 0.0166483 0.00305798 0.00556502 -0.978782 0.204807 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 2.3177e-05 0.0133593 4.0002 0.0151613 0.167893 +EDGE_SE3:QUAT 11 1645 2.57345 0.86924 0.00454204 0.00585219 0.00249895 -0.997819 0.0657003 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99985 4.13797e-06 0.023565 4.00056 0.00682664 0.0174173 +EDGE_SE3:QUAT 12 1645 -1.33729 0.795487 -0.0376276 -0.00946563 -0.00311902 0.998302 0.057388 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.00023033 0.0380445 4.0013 0.0167131 0.0136065 +EDGE_SE3:QUAT 13 1645 -5.51538 1.2153 -0.0620265 -0.00920274 -0.00717267 0.993084 0.116823 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 0.000393761 0.0374706 4.00076 0.0362121 0.0552765 +EDGE_SE3:QUAT 1646 1647 4.30177 -0.736715 0.0123525 0.00454295 -0.000623928 -0.139559 0.990203 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99992 1.19082e-05 0.00266304 4 -0.000366199 3.92209 +EDGE_SE3:QUAT 9 1646 6.29759 2.14226 0.00706908 0.0043935 0.00463255 -0.983302 0.181869 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -1.27805e-05 0.0186465 4.00038 0.0108361 0.132427 +EDGE_SE3:QUAT 10 1646 2.50965 1.0401 -0.00614604 0.00235437 0.00600132 -0.998858 0.0473332 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 6.17281e-05 0.00945462 3.99998 0.0229819 0.00911647 +EDGE_SE3:QUAT 11 1646 -1.56252 1.02355 -0.0350646 -0.00561118 -0.00325137 0.995653 0.0929103 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 0.000124559 0.0227132 4.00037 0.0168629 0.0347308 +EDGE_SE3:QUAT 12 1646 -5.27903 1.93672 -0.103722 -0.00906267 -0.00438426 0.976587 0.214887 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 0.00040898 0.0383306 4.00071 0.0304155 0.185323 +EDGE_SE3:QUAT 1647 1648 4.3708 -0.561232 0.00753037 0.00390513 0.00439183 -0.0896923 0.995952 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00032 2.94998e-05 0.0388947 3.9999 -0.00179899 3.9682 +EDGE_SE3:QUAT 8 1647 6.08425 1.78125 0.0199025 0.00208025 0.00830931 -0.991584 0.12918 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 0.000104021 0.00867074 3.99993 0.0297457 0.0669943 +EDGE_SE3:QUAT 9 1647 2.01279 1.27681 -0.0207622 0.00417169 0.000353982 -0.999074 0.0428286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99993 -1.20519e-05 0.0167327 4.00028 -1.73195e-05 0.00740727 +EDGE_SE3:QUAT 10 1647 -1.82708 1.35269 -0.00352222 -0.00117633 -0.00132619 0.995761 0.0919646 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 7.16493e-06 0.00475639 4.00001 0.00605107 0.0338448 +EDGE_SE3:QUAT 11 1647 -5.62359 2.52428 -0.0679914 -0.00436507 0.00105027 0.973096 0.230356 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.0107e-05 0.0188966 4.0003 0.00396378 0.212354 +EDGE_SE3:QUAT 1648 1649 4.37412 -0.178264 0.0165824 0.00113546 -0.00400328 -0.0161481 0.999861 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -2.41526e-05 -0.0317954 3.99994 0.000256567 3.99921 +EDGE_SE3:QUAT 7 1648 6.18265 1.23585 0.04879 0.00834706 0.00627002 -0.997986 0.062577 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99968 0.000111913 0.0335953 4.00111 0.0206805 0.0160543 +EDGE_SE3:QUAT 8 1648 1.74706 1.21064 0.00524288 0.0062173 0.00509156 -0.999189 0.0394609 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99983 9.51599e-05 0.0249298 4.00057 0.0183312 0.00646841 +EDGE_SE3:QUAT 9 1648 -2.34762 1.46064 -0.0535503 -0.00892494 0.00322366 0.998861 0.0467576 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99967 -2.59852e-05 0.0358178 4.00129 -0.00949691 0.00908917 +EDGE_SE3:QUAT 10 1648 -5.95403 2.69279 -0.00508378 -0.00550117 0.00318545 0.983509 0.180747 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 7.62823e-05 0.0232062 4.00055 -0.00401876 0.130821 +EDGE_SE3:QUAT 1649 1650 4.25211 -0.0853315 0.00509129 -0.00220196 0.00410603 -0.00387816 0.999982 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 -3.75836e-05 0.0327467 3.99993 -6.43295e-05 4.00021 +EDGE_SE3:QUAT 6 1649 5.91158 0.752835 -0.0102756 -0.000667923 0.00371734 -0.999008 0.0443746 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -5.23034e-06 -0.00267701 3.99995 0.0150328 0.0079348 +EDGE_SE3:QUAT 7 1649 1.83169 0.878425 -0.00373686 0.00457592 0.00554793 -0.998881 0.0467488 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 8.6032e-05 0.0183685 4.00027 0.0203653 0.00893028 +EDGE_SE3:QUAT 8 1649 -2.59846 1.0354 -0.0332926 0.00275685 0.00352043 -0.999701 0.0240286 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99997 3.64642e-05 0.0110375 4.00008 0.0135323 0.00238577 +EDGE_SE3:QUAT 9 1649 -6.63096 2.03369 -0.123838 -0.00552368 0.00457362 0.998022 0.0624485 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99986 -5.96776e-05 0.0222323 4.00048 -0.0153702 0.0157827 +EDGE_SE3:QUAT 1650 1651 4.08575 -0.0925979 0.0155685 0.00527495 0.00647773 0.00636033 0.999945 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00055 0.000141652 0.0514213 3.99984 0.000168416 4.0005 +EDGE_SE3:QUAT 5 1650 6.21574 0.321562 -0.0366492 -0.00416862 0.0105567 -0.999315 0.0352112 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -0.000155964 -0.0167044 3.99976 0.0432694 0.00549779 +EDGE_SE3:QUAT 6 1650 1.66239 0.480254 0.00021061 0.00330497 0.00613624 -0.999161 0.0403607 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 8.05394e-05 0.0132559 4.00006 0.0233809 0.00669684 +EDGE_SE3:QUAT 7 1650 -2.38631 0.580169 -0.0447687 0.00864521 0.00753401 -0.99901 0.0429944 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99966 0.0001956 0.0346816 4.0011 0.0270399 0.00787848 +EDGE_SE3:QUAT 8 1650 -6.82493 0.948098 -0.0528068 0.00662836 0.00573836 -0.999748 0.0206518 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 0.000134863 0.0265312 4.00061 0.0218394 0.00200132 +EDGE_SE3:QUAT 1651 1652 4.1204 -0.0152244 0.0151391 -0.00753493 0.00135794 0.00300757 0.999966 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9998 -4.21514e-05 0.0111345 3.99999 1.65335e-05 3.99999 +EDGE_SE3:QUAT 4 1651 6.27522 0.0188935 0.00773556 0.00247589 -0.000594239 -0.999368 0.0354571 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 -1.08723e-05 0.00992197 4.00009 -0.00307102 0.00505583 +EDGE_SE3:QUAT 5 1651 2.12195 0.108139 0.00978795 0.00259779 0.00553805 -0.999142 0.0409544 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99996 5.93688e-05 0.0104207 4.00001 0.0212103 0.00684892 +EDGE_SE3:QUAT 6 1651 -2.40022 0.216895 -0.00683457 0.0101848 0.000811627 -0.998873 0.0463557 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99959 -8.27868e-05 0.0408688 4.00167 -0.000540699 0.009014 +EDGE_SE3:QUAT 7 1651 -6.44917 0.326625 -0.0791651 0.0156608 0.00366028 -0.998661 0.0491758 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99899 -6.2069e-05 0.0628652 4.00398 0.00841573 0.0106815 +EDGE_SE3:QUAT 1652 1653 4.15696 -0.240089 0.0484517 0.00579958 0.0068985 -0.0778036 0.996928 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00077 7.72162e-05 0.0600903 3.99977 -0.00239498 3.97669 +EDGE_SE3:QUAT 3 1652 6.38393 -0.293055 -0.08547 -0.00617668 0.015476 -0.998723 0.047696 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99991 -0.000321448 -0.0247858 3.99945 0.0639054 0.0102768 +EDGE_SE3:QUAT 4 1652 2.18256 -0.269426 0.00327167 0.0034979 0.0070275 -0.999227 0.0385315 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 9.98439e-05 0.0140268 4.00005 0.0269306 0.00616958 +EDGE_SE3:QUAT 5 1652 -1.96145 -0.17553 2.08753e-05 0.00404134 0.0135461 -0.998932 0.0439796 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99989 0.000259037 0.0162258 3.99965 0.0525052 0.00849343 +EDGE_SE3:QUAT 6 1652 -6.4326 -0.112862 -0.0837512 0.0123166 0.00977851 -0.998623 0.0500463 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99931 0.000319934 0.0494601 4.00232 0.0339789 0.0109211 +EDGE_SE3:QUAT 1653 1654 3.92796 -0.955001 0.0183337 -0.00199735 -0.011907 -0.252282 0.967578 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.0021 -0.000750329 -0.0921413 3.99963 0.0114869 3.74753 +EDGE_SE3:QUAT 2 1653 6.54774 -0.419841 0.0728622 -0.015764 -0.00801408 0.999736 0.0146745 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99904 0.000585279 0.0630761 4.00363 0.0339343 0.00214398 +EDGE_SE3:QUAT 3 1653 2.22521 -0.473007 0.0193753 0.000248367 -0.00955622 0.999498 0.0302105 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4 -3.12883e-05 -0.000997276 3.99964 0.038076 0.00401375 +EDGE_SE3:QUAT 4 1653 -1.9398 -0.368043 0.0222743 -0.0100867 -0.00149985 0.999187 0.0390054 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99961 0.000153452 0.0404366 4.00158 0.00912477 0.00651595 +EDGE_SE3:QUAT 5 1653 -6.09442 -0.317928 0.0120939 -0.0100738 -0.00834225 0.999353 0.0334923 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99964 0.000393381 0.0403642 4.00121 0.0359893 0.00521869 +EDGE_SE3:QUAT 1654 1655 4.10279 -1.20909 -0.0179888 0.0034339 0.00747838 -0.259653 0.965667 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00098 -0.000289674 0.0641131 3.9998 -0.00851073 3.73135 +EDGE_SE3:QUAT 1 1654 6.80609 0.55539 0.0531633 -0.0015676 -0.0165327 0.964748 0.262652 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99981 -0.000390547 0.00448336 3.99921 0.0580667 0.276869 +EDGE_SE3:QUAT 2 1654 2.65452 0.638271 -0.00205286 -0.00160224 -0.0135109 0.963817 0.266219 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99988 -0.000258839 0.00501121 3.99945 0.0478768 0.284122 +EDGE_SE3:QUAT 3 1654 -1.6109 0.704777 0.0640753 0.0140825 -0.011224 0.959526 0.281045 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99907 0.00106588 -0.0645776 4.00408 0.00711225 0.317102 +EDGE_SE3:QUAT 4 1654 -5.77663 0.87977 -0.0293589 0.00229129 -0.00664123 0.957117 0.289618 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -2.0022e-05 -0.0115343 4.00018 0.0162986 0.33563 +EDGE_SE3:QUAT 1655 1656 3.92864 -0.702978 0.000953771 -0.00371143 0.00142667 -0.14937 0.988773 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99995 -5.96439e-06 0.0044798 4 -0.000159379 3.91076 +EDGE_SE3:QUAT 1 1655 3.89772 3.67134 0.0944305 -0.00320542 -0.0112546 0.86339 0.504402 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99976 -0.000214898 0.00514812 3.99982 0.0287344 1.01804 +EDGE_SE3:QUAT 2 1655 -0.23959 3.78344 0.0247867 -0.00440455 -0.00811962 0.861494 0.507684 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.9999 -0.000154026 0.0145021 3.99976 0.0268335 1.03129 +EDGE_SE3:QUAT 3 1655 -4.38741 3.93031 0.192891 0.0102101 -0.0020792 0.853815 0.520472 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00025 0.00089524 -0.0561254 4.00086 -0.0277578 1.08466 +EDGE_SE3:QUAT 1656 1657 4.07595 -0.477979 -0.00176339 0.0038547 -0.00102997 -0.0909059 0.995851 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99994 -5.672e-06 -0.00395585 4 0.000114573 3.96695 +EDGE_SE3:QUAT 1657 1658 4.19805 -0.240542 0.0378044 0.00229015 0.0030218 -0.0257697 0.999661 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 4.00013 2.28284e-05 0.0248589 3.99996 -0.000322747 3.9975 +EDGE_SE3:QUAT 1658 1659 4.24184 -0.061526 0.0197744 0.00578879 -0.00019708 -0.00536722 0.999969 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99987 -3.12739e-06 -0.00120367 4 2.90013e-06 3.99989 +EDGE_SE3:QUAT 1659 1660 4.21884 -0.184745 0.00856371 0.00395105 0.00187026 0.0429952 0.999066 1 0 0 0 0 0 1 0 0 0 0 1 0 0 0 3.99998 2.69577e-05 0.0128844 3.99999 0.000262348 3.99265 diff --git a/examples/data/sphere2500.g2o b/examples/data/sphere2500.g2o new file mode 100644 index 0000000..0b5e6ec --- /dev/null +++ b/examples/data/sphere2500.g2o @@ -0,0 +1,7449 @@ +VERTEX_SE3:QUAT 0 0 0 0 0 0 0 1 +VERTEX_SE3:QUAT 1 0.341895 -0.0416997 0.0330394 -0.00189341 0.00395691 0.0899835 0.995934 +VERTEX_SE3:QUAT 2 0.541643 0.135005 -0.0677869 -0.00371534 0.0122879 0.145258 0.98931 +VERTEX_SE3:QUAT 3 0.694297 0.0744828 -0.30675 -0.00363286 0.00986223 0.20475 0.978758 +VERTEX_SE3:QUAT 4 0.807006 0.209447 -0.454577 0.000670192 0.0111137 0.279124 0.96019 +VERTEX_SE3:QUAT 5 1.1155 0.328033 -0.5458 -0.00721036 0.0122286 0.359766 0.932935 +VERTEX_SE3:QUAT 6 1.28287 0.446964 -0.56423 -0.0122976 0.0138542 0.389026 0.92104 +VERTEX_SE3:QUAT 7 1.61945 0.475239 -0.692748 -0.0098214 0.0256639 0.45716 0.88896 +VERTEX_SE3:QUAT 8 1.99578 0.624088 -0.527553 -0.011752 0.0289959 0.509591 0.859848 +VERTEX_SE3:QUAT 9 2.20027 0.828242 -0.576724 -0.00556993 0.033619 0.543666 0.83861 +VERTEX_SE3:QUAT 10 2.40722 1.20964 -0.702838 -0.00754617 0.0243632 0.606592 0.794604 +VERTEX_SE3:QUAT 11 2.50465 1.6444 -0.782773 -0.00851642 0.0240438 0.658328 0.752299 +VERTEX_SE3:QUAT 12 2.58924 2.23802 -0.843049 -0.00178174 0.0292402 0.71242 0.701141 +VERTEX_SE3:QUAT 13 2.62724 2.32773 -0.753814 0.00149169 0.0283458 0.745117 0.66633 +VERTEX_SE3:QUAT 14 2.67953 2.74265 -0.757983 -0.00323224 0.0285368 0.772877 0.633905 +VERTEX_SE3:QUAT 15 2.49101 3.055 -0.844536 0.00753528 0.0293469 0.813113 0.581316 +VERTEX_SE3:QUAT 16 2.56229 3.56207 -0.843583 0.0034162 0.0251413 0.856538 0.515459 +VERTEX_SE3:QUAT 17 2.33413 4.02276 -0.869176 0.00235891 0.0222425 0.909681 0.414705 +VERTEX_SE3:QUAT 18 1.79462 4.2637 -0.765716 -0.00764504 0.0241991 0.938036 0.345607 +VERTEX_SE3:QUAT 19 1.46315 4.40927 -0.741374 -0.0110913 0.0261495 0.942762 0.332255 +VERTEX_SE3:QUAT 20 1.1325 4.74652 -0.726389 -0.0162105 0.0265565 0.953561 0.299587 +VERTEX_SE3:QUAT 21 0.574417 4.95649 -0.565477 -0.0274374 0.0328144 0.961679 0.27082 +VERTEX_SE3:QUAT 22 0.251562 5.34515 -0.632288 -0.0363475 0.0379309 0.969961 0.237518 +VERTEX_SE3:QUAT 23 -0.086921 5.70122 -0.570482 -0.040565 0.0388073 0.985664 0.159104 +VERTEX_SE3:QUAT 24 -0.522548 5.84288 -0.613185 -0.0428235 0.0503031 0.994406 0.0824123 +VERTEX_SE3:QUAT 25 -1.01622 5.97466 -0.608022 -0.0405851 0.05631 0.997534 -0.0103459 +VERTEX_SE3:QUAT 26 -1.41731 5.98775 -0.566796 -0.0390711 0.0603701 0.995219 -0.066086 +VERTEX_SE3:QUAT 27 -1.97731 5.99601 -0.596542 -0.0397471 0.0622153 0.98772 -0.137691 +VERTEX_SE3:QUAT 28 -2.35698 5.88328 -0.765671 -0.0453045 0.0674737 0.97221 -0.219551 +VERTEX_SE3:QUAT 29 -2.65196 5.63803 -0.672271 -0.0470412 0.062036 0.96143 -0.263802 +VERTEX_SE3:QUAT 30 -3.05787 5.4548 -0.779403 -0.0439046 0.0675069 0.93667 -0.340828 +VERTEX_SE3:QUAT 31 -3.49912 5.2846 -0.777169 -0.0497339 0.070032 0.908499 -0.408965 +VERTEX_SE3:QUAT 32 -3.76041 5.07893 -0.792044 -0.0532223 0.0792294 0.881312 -0.462796 +VERTEX_SE3:QUAT 33 -4.3202 4.60301 -0.804975 -0.0553871 0.0764029 0.839035 -0.535831 +VERTEX_SE3:QUAT 34 -4.35649 4.14707 -0.773416 -0.0471471 0.0745967 0.798175 -0.595927 +VERTEX_SE3:QUAT 35 -4.39395 3.78375 -0.95921 -0.0400931 0.0691556 0.739842 -0.668015 +VERTEX_SE3:QUAT 36 -4.47306 3.2628 -1.11204 -0.0369472 0.0601778 0.685224 -0.724901 +VERTEX_SE3:QUAT 37 -4.44716 2.93632 -1.04583 -0.0373053 0.0606492 0.609555 -0.78954 +VERTEX_SE3:QUAT 38 -4.41146 2.56073 -1.15144 -0.0421974 0.0545489 0.581981 -0.810273 +VERTEX_SE3:QUAT 39 -4.17554 1.99264 -1.0171 -0.0454168 0.0594126 0.526518 -0.846868 +VERTEX_SE3:QUAT 40 -3.74958 1.49129 -1.01101 -0.0402989 0.0499153 0.492173 -0.86813 +VERTEX_SE3:QUAT 41 -3.43285 1.03806 -1.01704 -0.0466887 0.0454049 0.451239 -0.890024 +VERTEX_SE3:QUAT 42 -2.89324 0.609977 -1.07996 -0.0421607 0.0388651 0.382632 -0.92212 +VERTEX_SE3:QUAT 43 -2.42101 0.371722 -1.06172 -0.0409636 0.034039 0.338117 -0.939596 +VERTEX_SE3:QUAT 44 -2.0125 0.0850927 -1.11925 -0.0445392 0.0218744 0.329831 -0.942735 +VERTEX_SE3:QUAT 45 -1.82644 -0.259844 -1.38525 -0.0470467 0.00794119 0.276111 -0.959941 +VERTEX_SE3:QUAT 46 -1.38012 -0.582296 -1.35068 -0.0384994 0.0010287 0.227696 -0.97297 +VERTEX_SE3:QUAT 47 -0.878737 -0.91575 -1.44105 -0.0378097 0.000519079 0.150333 -0.987912 +VERTEX_SE3:QUAT 48 -0.278326 -1.1237 -1.42451 -0.0358072 -0.00327021 0.0754474 -0.996501 +VERTEX_SE3:QUAT 49 0.241054 -1.31932 -1.43394 -0.0397158 -0.0148851 -0.0047885 -0.999089 +VERTEX_SE3:QUAT 50 1.02217 -1.23565 -1.59068 -0.0427026 -0.0200372 -0.0940541 -0.994449 +VERTEX_SE3:QUAT 51 1.73193 -1.35493 -1.48911 -0.0495285 -0.01995 -0.142626 -0.988335 +VERTEX_SE3:QUAT 52 2.7166 -1.19537 -1.44748 -0.0454633 -0.0239459 -0.197469 -0.978962 +VERTEX_SE3:QUAT 53 3.16979 -0.865486 -1.61067 -0.0434707 -0.029388 -0.215257 -0.975147 +VERTEX_SE3:QUAT 54 3.72417 -0.539081 -1.58489 -0.047344 -0.0311607 -0.252334 -0.965979 +VERTEX_SE3:QUAT 55 4.26613 -0.232608 -1.65565 -0.0460708 -0.0390648 -0.302048 -0.951377 +VERTEX_SE3:QUAT 56 4.91103 0.167998 -1.84245 -0.0469212 -0.0422937 -0.360423 -0.930648 +VERTEX_SE3:QUAT 57 5.4651 0.723295 -1.79634 -0.0503115 -0.0545286 -0.387305 -0.918961 +VERTEX_SE3:QUAT 58 5.88013 1.25208 -1.95912 -0.053379 -0.0580738 -0.42242 -0.902961 +VERTEX_SE3:QUAT 59 6.35487 1.85242 -2.07791 -0.0518249 -0.0671336 -0.477575 -0.874488 +VERTEX_SE3:QUAT 60 6.87724 2.43275 -2.17598 -0.0543934 -0.0632144 -0.545562 -0.833911 +VERTEX_SE3:QUAT 61 7.06199 2.86937 -2.30091 -0.0637218 -0.0641357 -0.61899 -0.780178 +VERTEX_SE3:QUAT 62 7.20538 3.6555 -2.27946 -0.0600394 -0.0705409 -0.676426 -0.730662 +VERTEX_SE3:QUAT 63 7.13617 4.40282 -2.37777 -0.0647586 -0.0681625 -0.741396 -0.664449 +VERTEX_SE3:QUAT 64 6.88196 5.06827 -2.25668 -0.0641883 -0.0703457 -0.801933 -0.589775 +VERTEX_SE3:QUAT 65 6.4435 5.90061 -2.22981 -0.0662571 -0.0683961 -0.829015 -0.551058 +VERTEX_SE3:QUAT 66 5.9157 6.44621 -2.2289 -0.0645185 -0.0666627 -0.860306 -0.501265 +VERTEX_SE3:QUAT 67 5.66427 7.03826 -2.23396 -0.0577811 -0.07001 -0.884446 -0.457728 +VERTEX_SE3:QUAT 68 5.11195 7.69146 -2.09365 -0.0574741 -0.0770405 -0.918614 -0.383288 +VERTEX_SE3:QUAT 69 4.44484 8.21282 -2.2057 -0.0482726 -0.0727001 -0.941263 -0.326202 +VERTEX_SE3:QUAT 70 3.96536 8.67861 -2.36843 -0.0432583 -0.0701504 -0.952703 -0.292514 +VERTEX_SE3:QUAT 71 3.39966 9.10789 -2.42823 -0.045403 -0.0700702 -0.963835 -0.253083 +VERTEX_SE3:QUAT 72 2.79079 9.54749 -2.38548 -0.0587478 -0.0626255 -0.980757 -0.175333 +VERTEX_SE3:QUAT 73 1.95465 9.89706 -2.18558 -0.0580239 -0.0641704 -0.99091 -0.103017 +VERTEX_SE3:QUAT 74 1.44299 9.98831 -2.17416 -0.0633884 -0.0667356 -0.993342 -0.069282 +VERTEX_SE3:QUAT 75 0.625415 10.2328 -2.24288 -0.0547642 -0.0623834 -0.996503 0.00958181 +VERTEX_SE3:QUAT 76 -0.127815 10.2965 -2.22042 -0.0460494 -0.0566063 -0.99501 0.0680507 +VERTEX_SE3:QUAT 77 -1.00178 10.1326 -1.98764 -0.02968 -0.0479574 -0.989152 0.135641 +VERTEX_SE3:QUAT 78 -1.70884 9.96666 -1.93477 -0.026368 -0.0407356 -0.987281 0.151402 +VERTEX_SE3:QUAT 79 -2.41656 9.74354 -2.06621 -0.016207 -0.0366114 -0.975536 0.216162 +VERTEX_SE3:QUAT 80 -3.15499 9.26144 -2.1881 -0.00608404 -0.0419855 -0.955182 0.292964 +VERTEX_SE3:QUAT 81 -3.79656 8.56976 -2.18398 0.000267636 -0.0450733 -0.951782 0.303446 +VERTEX_SE3:QUAT 82 -4.39076 8.2685 -2.12883 0.00188647 -0.0374286 -0.926926 0.373369 +VERTEX_SE3:QUAT 83 -4.96543 7.70241 -2.03215 0.0150986 -0.0394582 -0.906255 0.420615 +VERTEX_SE3:QUAT 84 -5.65704 7.00684 -2.0497 0.0105164 -0.0427879 -0.898269 0.437232 +VERTEX_SE3:QUAT 85 -6.25126 6.29045 -1.98928 0.0163873 -0.0432396 -0.876764 0.478692 +VERTEX_SE3:QUAT 86 -6.6158 5.51573 -2.04761 0.0179569 -0.0438527 -0.840918 0.539083 +VERTEX_SE3:QUAT 87 -7.00849 4.79965 -1.94181 0.0247629 -0.0417666 -0.807696 0.587597 +VERTEX_SE3:QUAT 88 -7.2327 3.72003 -2.08742 0.0357475 -0.0359578 -0.764381 0.642768 +VERTEX_SE3:QUAT 89 -7.35654 2.77554 -2.01197 0.0428213 -0.0293352 -0.713958 0.698262 +VERTEX_SE3:QUAT 90 -7.36115 1.87752 -2.05215 0.0474389 -0.0186838 -0.684337 0.727381 +VERTEX_SE3:QUAT 91 -7.23121 0.900872 -2.15663 0.0580778 -0.0200174 -0.63186 0.772644 +VERTEX_SE3:QUAT 92 -7.09988 -0.280726 -2.36116 0.0671784 -0.0237015 -0.585646 0.807431 +VERTEX_SE3:QUAT 93 -6.66154 -1.15471 -2.42773 0.070066 -0.0179534 -0.560224 0.825178 +VERTEX_SE3:QUAT 94 -6.32243 -2.01069 -2.75511 0.0766221 -0.0139347 -0.498963 0.863117 +VERTEX_SE3:QUAT 95 -5.78993 -2.77667 -2.84262 0.0869896 -0.0106479 -0.459274 0.883961 +VERTEX_SE3:QUAT 96 -5.21003 -3.55803 -3.00233 0.0828717 -0.0054295 -0.377347 0.922341 +VERTEX_SE3:QUAT 97 -4.45275 -4.39205 -3.04073 0.0934585 -0.00272145 -0.298484 0.949824 +VERTEX_SE3:QUAT 98 -3.61457 -4.79355 -3.17268 0.0895507 -0.00737589 -0.265981 0.959781 +VERTEX_SE3:QUAT 99 -2.74742 -5.24969 -3.18186 0.0972232 -0.0030355 -0.238616 0.96623 +VERTEX_SE3:QUAT 100 -1.81793 -5.67934 -3.28281 0.0970788 -0.00400955 -0.191454 0.976681 +VERTEX_SE3:QUAT 101 -0.750895 -6.0387 -3.51056 0.105982 -0.012449 -0.131749 0.985523 +VERTEX_SE3:QUAT 102 0.178034 -6.31752 -3.4333 0.116007 -0.00408815 -0.0828274 0.98978 +VERTEX_SE3:QUAT 103 1.21189 -6.44534 -3.53903 0.116043 -0.0115939 -0.0183369 0.993007 +VERTEX_SE3:QUAT 104 2.24007 -6.42449 -3.24474 0.109462 0.00109515 0.0517511 0.992642 +VERTEX_SE3:QUAT 105 3.30859 -6.15204 -3.43475 0.111304 0.003213 0.0765486 0.990829 +VERTEX_SE3:QUAT 106 4.29673 -5.79294 -3.52955 0.105904 0.0113163 0.115238 0.987612 +VERTEX_SE3:QUAT 107 5.27272 -5.47859 -3.56836 0.101256 0.0160019 0.177826 0.978708 +VERTEX_SE3:QUAT 108 6.15226 -5.03185 -3.61787 0.0980758 0.0213218 0.213696 0.971731 +VERTEX_SE3:QUAT 109 7.1149 -4.60963 -3.64556 0.103639 0.0147431 0.28169 0.953778 +VERTEX_SE3:QUAT 110 8.15639 -4.00099 -3.68095 0.0984384 0.0107662 0.349282 0.93177 +VERTEX_SE3:QUAT 111 8.78857 -3.26546 -3.68388 0.0974034 0.0191175 0.374462 0.921914 +VERTEX_SE3:QUAT 112 9.53355 -2.51361 -3.87706 0.0906402 0.0245886 0.457779 0.884092 +VERTEX_SE3:QUAT 113 10.2754 -1.67194 -3.92814 0.089698 0.030756 0.508494 0.855828 +VERTEX_SE3:QUAT 114 10.8598 -0.686338 -3.8599 0.092985 0.0369122 0.550162 0.829044 +VERTEX_SE3:QUAT 115 11.273 0.364685 -4.03555 0.0868291 0.0340635 0.62973 0.771194 +VERTEX_SE3:QUAT 116 11.4719 1.42876 -4.16467 0.0745437 0.0360667 0.688706 0.720296 +VERTEX_SE3:QUAT 117 11.6839 2.61545 -4.15294 0.0639851 0.0411498 0.726591 0.682845 +VERTEX_SE3:QUAT 118 11.5462 3.78662 -4.01677 0.0620837 0.0497411 0.755607 0.650177 +VERTEX_SE3:QUAT 119 11.3059 5.03917 -4.05807 0.057105 0.0501901 0.793341 0.604011 +VERTEX_SE3:QUAT 120 10.9718 6.18184 -4.006 0.0464785 0.052314 0.857167 0.510263 +VERTEX_SE3:QUAT 121 10.3189 7.24377 -3.89373 0.0392482 0.0565309 0.886354 0.457865 +VERTEX_SE3:QUAT 122 9.5881 8.31827 -3.77251 0.0408039 0.0649341 0.900004 0.429083 +VERTEX_SE3:QUAT 123 8.76726 9.16474 -3.65101 0.0362814 0.0700761 0.923438 0.375548 +VERTEX_SE3:QUAT 124 7.69176 10.1311 -3.48876 0.0350339 0.0651638 0.948394 0.308344 +VERTEX_SE3:QUAT 125 6.73965 10.7922 -3.54733 0.0294232 0.0653565 0.961845 0.26404 +VERTEX_SE3:QUAT 126 5.82356 11.5034 -3.60681 0.025845 0.060835 0.977469 0.200465 +VERTEX_SE3:QUAT 127 4.62949 12.0516 -3.56286 0.0179586 0.0751415 0.980814 0.178981 +VERTEX_SE3:QUAT 128 3.54135 12.5045 -3.59232 0.00903254 0.0782368 0.990365 0.113907 +VERTEX_SE3:QUAT 129 2.33961 12.8812 -3.53073 -0.00917748 0.0900162 0.991372 0.0948433 +VERTEX_SE3:QUAT 130 1.12419 13.0471 -3.55184 -0.0199933 0.0886916 0.994495 0.0520859 +VERTEX_SE3:QUAT 131 -0.256626 13.1178 -3.71309 -0.0315488 0.0883137 0.995587 0.0033444 +VERTEX_SE3:QUAT 132 -1.39889 13.0748 -3.73472 -0.0310411 0.0875059 0.991603 -0.0900153 +VERTEX_SE3:QUAT 133 -2.72487 12.7348 -3.77057 -0.0323219 0.0936277 0.989086 -0.109079 +VERTEX_SE3:QUAT 134 -4.0853 12.4155 -3.79078 -0.03488 0.0961409 0.975915 -0.192694 +VERTEX_SE3:QUAT 135 -5.16664 11.8055 -3.84181 -0.0345416 0.10032 0.956769 -0.270806 +VERTEX_SE3:QUAT 136 -6.39329 11.107 -3.88028 -0.0325186 0.0999654 0.930354 -0.35127 +VERTEX_SE3:QUAT 137 -7.15023 10.2216 -3.79543 -0.0403919 0.101879 0.905122 -0.410785 +VERTEX_SE3:QUAT 138 -8.10312 9.15726 -3.95197 -0.0519775 0.0945914 0.894062 -0.434747 +VERTEX_SE3:QUAT 139 -8.84374 8.12904 -4.01213 -0.0592531 0.0926076 0.844448 -0.524234 +VERTEX_SE3:QUAT 140 -9.54598 6.8594 -3.93664 -0.0673517 0.0884933 0.809887 -0.575947 +VERTEX_SE3:QUAT 141 -10.1832 5.6667 -3.98372 -0.0701024 0.08969 0.770736 -0.626903 +VERTEX_SE3:QUAT 142 -10.4033 4.33151 -3.93237 -0.076289 0.0780231 0.727456 -0.677422 +VERTEX_SE3:QUAT 143 -10.4642 2.84618 -3.83437 -0.0899533 0.0769315 0.6874 -0.716569 +VERTEX_SE3:QUAT 144 -10.4928 1.37382 -3.89534 -0.103394 0.0712196 0.654916 -0.745199 +VERTEX_SE3:QUAT 145 -10.3332 -0.0695058 -3.93333 -0.105967 0.0645796 0.585091 -0.801417 +VERTEX_SE3:QUAT 146 -10.0917 -1.45065 -4.05124 -0.110604 0.0654474 0.516096 -0.846834 +VERTEX_SE3:QUAT 147 -9.29063 -2.80805 -4.01034 -0.105478 0.0674447 0.422225 -0.897804 +VERTEX_SE3:QUAT 148 -8.50534 -3.80677 -3.96519 -0.112285 0.0629318 0.349814 -0.927934 +VERTEX_SE3:QUAT 149 -7.37145 -4.6416 -3.98249 -0.11623 0.0584297 0.281741 -0.950631 +VERTEX_SE3:QUAT 150 -5.94241 -5.26095 -3.9113 -0.116798 0.0581778 0.193116 -0.972461 +VERTEX_SE3:QUAT 151 -4.52501 -5.7604 -3.80893 -0.113676 0.0481795 0.13189 -0.983545 +VERTEX_SE3:QUAT 152 -2.96556 -5.91252 -3.70048 -0.115098 0.0290548 0.085079 -0.989277 +VERTEX_SE3:QUAT 153 -1.58518 -6.18655 -3.61203 -0.118746 0.021047 0.0600421 -0.990884 +VERTEX_SE3:QUAT 154 -0.204245 -6.41239 -3.50458 -0.127133 0.00753905 0.00580513 -0.99184 +VERTEX_SE3:QUAT 155 1.17096 -6.40396 -3.46896 -0.127573 -0.00228345 -0.0454615 -0.990784 +VERTEX_SE3:QUAT 156 2.39021 -6.25984 -3.50323 -0.133 -0.011698 -0.104986 -0.985471 +VERTEX_SE3:QUAT 157 3.69932 -6.07798 -3.59016 -0.136516 -0.0178972 -0.131918 -0.981652 +VERTEX_SE3:QUAT 158 5.07491 -5.59702 -3.53703 -0.136847 -0.0268517 -0.217564 -0.966032 +VERTEX_SE3:QUAT 159 6.3764 -4.88691 -3.62379 -0.132212 -0.0320325 -0.299137 -0.944463 +VERTEX_SE3:QUAT 160 7.52651 -4.12721 -3.34327 -0.133203 -0.0409564 -0.357813 -0.923336 +VERTEX_SE3:QUAT 161 8.50641 -3.12668 -3.26015 -0.131827 -0.0520358 -0.418645 -0.897023 +VERTEX_SE3:QUAT 162 9.32657 -2.08022 -3.38924 -0.125066 -0.0601424 -0.457323 -0.878406 +VERTEX_SE3:QUAT 163 10.1991 -0.9379 -3.41684 -0.119215 -0.0670708 -0.545131 -0.827116 +VERTEX_SE3:QUAT 164 10.6587 0.35979 -3.25882 -0.121411 -0.0796626 -0.583572 -0.798973 +VERTEX_SE3:QUAT 165 11.127 1.75653 -3.21747 -0.117238 -0.085416 -0.626207 -0.766044 +VERTEX_SE3:QUAT 166 11.4376 3.11357 -3.30925 -0.110888 -0.0935192 -0.660529 -0.736655 +VERTEX_SE3:QUAT 167 11.6176 4.5293 -3.37076 -0.107232 -0.0923626 -0.695372 -0.704577 +VERTEX_SE3:QUAT 168 11.5751 5.99598 -3.56919 -0.106234 -0.0898403 -0.746858 -0.650266 +VERTEX_SE3:QUAT 169 11.4679 7.491 -3.41711 -0.0943572 -0.0960695 -0.79081 -0.597065 +VERTEX_SE3:QUAT 170 10.9402 8.96127 -3.2247 -0.0816288 -0.0982069 -0.818534 -0.560084 +VERTEX_SE3:QUAT 171 10.3515 10.4123 -3.28135 -0.0714835 -0.100249 -0.847128 -0.516928 +VERTEX_SE3:QUAT 172 9.62633 11.9387 -3.29557 -0.0595175 -0.101495 -0.869594 -0.479543 +VERTEX_SE3:QUAT 173 8.76821 13.2673 -3.32803 -0.0585373 -0.102495 -0.903041 -0.41302 +VERTEX_SE3:QUAT 174 7.56994 14.5118 -3.44072 -0.0491766 -0.105995 -0.931262 -0.345104 +VERTEX_SE3:QUAT 175 6.41033 15.6145 -3.3728 -0.0503328 -0.104542 -0.954005 -0.276428 +VERTEX_SE3:QUAT 176 4.93682 16.504 -3.34883 -0.043714 -0.108176 -0.973969 -0.19435 +VERTEX_SE3:QUAT 177 3.44634 17.0716 -3.13087 -0.0319994 -0.113788 -0.980893 -0.154524 +VERTEX_SE3:QUAT 178 1.83473 17.5806 -3.03529 -0.0330915 -0.106803 -0.991339 -0.0688777 +VERTEX_SE3:QUAT 179 0.352569 17.5232 -2.89783 -0.0251175 -0.105929 -0.994032 -0.00693022 +VERTEX_SE3:QUAT 180 -1.49827 17.626 -2.77302 -0.0193428 -0.109047 -0.990294 0.0839827 +VERTEX_SE3:QUAT 181 -3.11956 17.3776 -2.68137 -0.00361757 -0.109392 -0.984705 0.135559 +VERTEX_SE3:QUAT 182 -4.85591 16.9183 -2.50927 0.00770436 -0.105531 -0.977417 0.182919 +VERTEX_SE3:QUAT 183 -6.39631 16.2192 -2.63626 0.0165265 -0.102137 -0.961295 0.255356 +VERTEX_SE3:QUAT 184 -7.63909 15.3498 -2.54888 0.0294237 -0.0931536 -0.947008 0.305994 +VERTEX_SE3:QUAT 185 -8.98234 14.332 -2.56789 0.0472048 -0.0878109 -0.927912 0.359221 +VERTEX_SE3:QUAT 186 -10.3156 13.1733 -2.54971 0.0498245 -0.087495 -0.892245 0.440183 +VERTEX_SE3:QUAT 187 -11.0433 11.8345 -2.61498 0.0653528 -0.0902643 -0.856228 0.504435 +VERTEX_SE3:QUAT 188 -12.0503 10.3663 -2.59999 0.0874934 -0.0842436 -0.848057 0.515798 +VERTEX_SE3:QUAT 189 -12.7142 8.91827 -2.78367 0.100741 -0.0795306 -0.818835 0.559496 +VERTEX_SE3:QUAT 190 -13.4405 7.30661 -3.01331 0.113651 -0.0750444 -0.795321 0.590692 +VERTEX_SE3:QUAT 191 -13.9192 5.56405 -3.1519 0.12219 -0.0683238 -0.768944 0.6238 +VERTEX_SE3:QUAT 192 -14.2236 3.89107 -3.45134 0.127277 -0.0656408 -0.727448 0.671052 +VERTEX_SE3:QUAT 193 -14.3694 2.26478 -3.47948 0.141405 -0.063771 -0.691145 0.705873 +VERTEX_SE3:QUAT 194 -14.3174 0.435911 -3.51495 0.152668 -0.0537815 -0.652247 0.740523 +VERTEX_SE3:QUAT 195 -13.9961 -1.06116 -3.79411 0.169373 -0.0545919 -0.594761 0.783959 +VERTEX_SE3:QUAT 196 -13.3698 -2.73243 -3.89491 0.174187 -0.0421803 -0.55632 0.811411 +VERTEX_SE3:QUAT 197 -12.9318 -4.32377 -4.12399 0.177964 -0.0434424 -0.512892 0.83868 +VERTEX_SE3:QUAT 198 -11.927 -5.6852 -4.40073 0.185329 -0.0474807 -0.463554 0.865168 +VERTEX_SE3:QUAT 199 -10.8362 -7.06844 -4.57881 0.194002 -0.0440373 -0.390146 0.899005 +VERTEX_SE3:QUAT 200 -9.27952 -8.20915 -4.66303 0.195577 -0.0341098 -0.348235 0.916143 +VERTEX_SE3:QUAT 201 -8.02348 -9.3134 -4.83549 0.198774 -0.0354099 -0.278146 0.939079 +VERTEX_SE3:QUAT 202 -6.32385 -10.1222 -4.80952 0.211052 -0.0337149 -0.18941 0.958355 +VERTEX_SE3:QUAT 203 -4.65083 -10.8371 -5.03165 0.209119 -0.0343116 -0.0918638 0.972961 +VERTEX_SE3:QUAT 204 -2.77296 -11.2345 -4.85672 0.212991 -0.0185456 -0.0530362 0.975437 +VERTEX_SE3:QUAT 205 -1.14457 -11.294 -4.83321 0.211365 -0.0165416 0.0234884 0.976985 +VERTEX_SE3:QUAT 206 0.817516 -11.2368 -4.64975 0.217633 -0.0162495 0.0802118 0.972593 +VERTEX_SE3:QUAT 207 2.79163 -10.9088 -4.55282 0.218484 -0.0111131 0.141249 0.9655 +VERTEX_SE3:QUAT 208 4.37892 -10.378 -4.52051 0.212479 -0.00344603 0.220235 0.952018 +VERTEX_SE3:QUAT 209 5.91453 -9.47994 -4.24587 0.215275 0.000164767 0.256449 0.94228 +VERTEX_SE3:QUAT 210 7.49525 -8.68798 -4.23735 0.213375 6.71102e-05 0.328462 0.9201 +VERTEX_SE3:QUAT 211 8.89738 -7.67126 -4.02005 0.209357 0.00117906 0.398652 0.892886 +VERTEX_SE3:QUAT 212 10.1471 -6.38901 -3.57612 0.202546 0.00678894 0.437189 0.876239 +VERTEX_SE3:QUAT 213 11.3462 -4.76913 -3.33969 0.192806 0.0137127 0.492411 0.848628 +VERTEX_SE3:QUAT 214 12.2794 -3.25862 -2.97653 0.188052 0.0317131 0.503501 0.842685 +VERTEX_SE3:QUAT 215 13.1613 -1.56424 -2.73218 0.18945 0.0338457 0.574133 0.795823 +VERTEX_SE3:QUAT 216 13.6437 0.224184 -2.50262 0.172398 0.0367069 0.63575 0.751501 +VERTEX_SE3:QUAT 217 13.8768 2.11401 -2.17076 0.151613 0.0383696 0.67997 0.716367 +VERTEX_SE3:QUAT 218 13.982 4.17488 -1.83262 0.146607 0.0403284 0.738618 0.656753 +VERTEX_SE3:QUAT 219 13.8465 5.81245 -1.53467 0.137373 0.0377646 0.794395 0.590457 +VERTEX_SE3:QUAT 220 13.304 7.65083 -1.21171 0.122124 0.0366897 0.834329 0.536316 +VERTEX_SE3:QUAT 221 12.4039 9.51145 -0.913738 0.116184 0.0373568 0.867158 0.482848 +VERTEX_SE3:QUAT 222 11.4185 10.9205 -0.602003 0.097445 0.0292763 0.906511 0.409738 +VERTEX_SE3:QUAT 223 10.0387 12.1352 -0.245808 0.08426 0.0331433 0.925663 0.367355 +VERTEX_SE3:QUAT 224 8.48229 13.2716 0.0806772 0.0743676 0.0343073 0.957272 0.277348 +VERTEX_SE3:QUAT 225 7.04421 14.2731 0.0742406 0.055802 0.0260295 0.982388 0.176416 +VERTEX_SE3:QUAT 226 5.20995 14.9303 0.271822 0.0373507 0.0279291 0.991257 0.123424 +VERTEX_SE3:QUAT 227 3.20258 15.3554 0.383289 0.0140488 0.024323 0.997894 0.0584689 +VERTEX_SE3:QUAT 228 1.13788 15.534 0.43398 -0.000306128 0.0242513 0.999691 0.00544511 +VERTEX_SE3:QUAT 229 -0.815358 15.5136 0.387762 -0.0191945 0.0238186 0.997697 -0.0605345 +VERTEX_SE3:QUAT 230 -2.82333 15.1905 0.237858 -0.0397754 0.0219538 0.990917 -0.126568 +VERTEX_SE3:QUAT 231 -4.66592 14.8297 0.0611793 -0.0527407 0.0223029 0.981816 -0.180991 +VERTEX_SE3:QUAT 232 -6.71729 14.222 -0.127464 -0.0624811 0.0147197 0.970126 -0.233953 +VERTEX_SE3:QUAT 233 -8.31176 13.3206 -0.267458 -0.0837188 0.00694893 0.952378 -0.29312 +VERTEX_SE3:QUAT 234 -9.7689 12.1777 -0.659249 -0.105386 0.00398981 0.929562 -0.353259 +VERTEX_SE3:QUAT 235 -11.3598 10.6244 -1.08861 -0.129389 -0.00363176 0.910694 -0.392277 +VERTEX_SE3:QUAT 236 -12.6788 9.21526 -1.55941 -0.155724 -0.00266825 0.872712 -0.462727 +VERTEX_SE3:QUAT 237 -13.5249 7.5715 -2.07928 -0.170085 -0.00343796 0.855429 -0.489184 +VERTEX_SE3:QUAT 238 -14.4603 5.84631 -2.82289 -0.188725 0.00383871 0.804297 -0.563449 +VERTEX_SE3:QUAT 239 -14.9931 4.26258 -3.42603 -0.202534 0.0124058 0.750551 -0.628888 +VERTEX_SE3:QUAT 240 -15.0738 2.06315 -4.0241 -0.222432 -0.000477241 0.717725 -0.659844 +VERTEX_SE3:QUAT 241 -15.2413 0.309732 -4.64994 -0.235929 -0.00734947 0.698539 -0.67552 +VERTEX_SE3:QUAT 242 -15.0901 -1.48646 -5.3748 -0.246955 -0.00914086 0.662793 -0.706849 +VERTEX_SE3:QUAT 243 -14.784 -3.45215 -6.00599 -0.258083 -0.00703412 0.59769 -0.759019 +VERTEX_SE3:QUAT 244 -14.1804 -5.50366 -6.70175 -0.274257 -0.00133588 0.528431 -0.803456 +VERTEX_SE3:QUAT 245 -13.2458 -7.21911 -7.58669 -0.284365 -0.00527456 0.496478 -0.820133 +VERTEX_SE3:QUAT 246 -12.1148 -8.99312 -8.41146 -0.301393 -0.0185932 0.453585 -0.838497 +VERTEX_SE3:QUAT 247 -10.7777 -10.4544 -8.88116 -0.316671 0.00660838 0.348512 -0.882165 +VERTEX_SE3:QUAT 248 -8.97525 -11.7927 -9.15877 -0.32506 0.0128293 0.265326 -0.90762 +VERTEX_SE3:QUAT 249 -7.08718 -12.6623 -9.53209 -0.333356 0.0110967 0.195394 -0.922264 +VERTEX_SE3:QUAT 250 -4.97925 -13.3131 -9.64458 -0.33942 0.0231214 0.118517 -0.932852 +VERTEX_SE3:QUAT 251 -2.7355 -13.8536 -9.82038 -0.335317 0.0239364 0.0571331 -0.940067 +VERTEX_SE3:QUAT 252 -0.560673 -14.0983 -9.93725 -0.335662 0.0185637 -0.00611852 -0.94178 +VERTEX_SE3:QUAT 253 1.52614 -14.0138 -9.88124 -0.337323 0.020046 -0.051693 -0.939755 +VERTEX_SE3:QUAT 254 3.59092 -13.5747 -9.7514 -0.332398 0.0203661 -0.124638 -0.934645 +VERTEX_SE3:QUAT 255 5.58796 -13.1052 -9.45113 -0.333138 0.0149448 -0.180919 -0.925237 +VERTEX_SE3:QUAT 256 7.52074 -12.5569 -9.08466 -0.334525 0.0127471 -0.228896 -0.914077 +VERTEX_SE3:QUAT 257 9.64238 -11.3826 -8.64585 -0.324915 0.0201545 -0.301933 -0.896025 +VERTEX_SE3:QUAT 258 11.5706 -10.0501 -8.19522 -0.31433 0.0180436 -0.347493 -0.883244 +VERTEX_SE3:QUAT 259 13.1152 -8.60679 -7.54008 -0.302699 0.0185164 -0.402797 -0.863589 +VERTEX_SE3:QUAT 260 14.5709 -6.9881 -6.81615 -0.290523 0.0125771 -0.445007 -0.846999 +VERTEX_SE3:QUAT 261 15.8415 -5.31673 -6.32987 -0.27824 0.0255523 -0.529958 -0.800672 +VERTEX_SE3:QUAT 262 16.7547 -3.46238 -5.5645 -0.261663 0.0283804 -0.601046 -0.754633 +VERTEX_SE3:QUAT 263 17.0818 -1.53405 -4.93254 -0.251416 0.0196601 -0.660419 -0.707283 +VERTEX_SE3:QUAT 264 17.2394 0.400657 -4.11226 -0.237279 0.0112066 -0.704566 -0.6687 +VERTEX_SE3:QUAT 265 17.3038 2.62339 -3.46503 -0.229424 0.0130571 -0.742066 -0.629708 +VERTEX_SE3:QUAT 266 16.9391 4.70724 -2.78825 -0.211546 0.0203338 -0.791186 -0.573463 +VERTEX_SE3:QUAT 267 16.5549 6.65756 -1.99374 -0.190795 0.0257746 -0.830491 -0.522701 +VERTEX_SE3:QUAT 268 15.6113 8.68996 -1.08534 -0.167299 0.035788 -0.874088 -0.454644 +VERTEX_SE3:QUAT 269 14.3512 10.444 -0.491765 -0.153317 0.0304098 -0.904548 -0.396689 +VERTEX_SE3:QUAT 270 12.9819 11.7876 0.176082 -0.141419 0.0379194 -0.933129 -0.328379 +VERTEX_SE3:QUAT 271 11.2056 12.9734 0.99092 -0.117127 0.0320165 -0.950937 -0.28456 +VERTEX_SE3:QUAT 272 9.50328 14.223 1.5561 -0.0969407 0.0290973 -0.970596 -0.218401 +VERTEX_SE3:QUAT 273 7.50698 15.0748 2.13283 -0.0776571 0.0303581 -0.988078 -0.129418 +VERTEX_SE3:QUAT 274 5.12243 15.507 2.3628 -0.047321 0.0299774 -0.996569 -0.0609312 +VERTEX_SE3:QUAT 275 2.96385 15.6273 2.6294 -0.022067 0.0315611 -0.998882 -0.0274047 +VERTEX_SE3:QUAT 276 0.617149 15.8284 2.67652 0.00744006 0.0269507 -0.999069 0.0328597 +VERTEX_SE3:QUAT 277 -1.33075 15.5478 2.59722 0.0299139 0.0390956 -0.996074 0.0735721 +VERTEX_SE3:QUAT 278 -3.54344 15.0893 2.30221 0.0533396 0.0416038 -0.986721 0.147664 +VERTEX_SE3:QUAT 279 -5.75363 14.4061 1.91145 0.0806087 0.0427076 -0.971389 0.219277 +VERTEX_SE3:QUAT 280 -7.6586 13.4818 1.44615 0.10368 0.0394259 -0.957282 0.267034 +VERTEX_SE3:QUAT 281 -9.50246 12.1816 1.1659 0.124005 0.0320955 -0.934105 0.333227 +VERTEX_SE3:QUAT 282 -11.2478 10.5812 0.464312 0.141059 0.0343855 -0.91528 0.375742 +VERTEX_SE3:QUAT 283 -12.938 8.82558 -0.0264483 0.160879 0.0321534 -0.881359 0.443048 +VERTEX_SE3:QUAT 284 -14.1636 6.94267 -0.855111 0.186012 0.0438015 -0.850487 0.490053 +VERTEX_SE3:QUAT 285 -15.2107 5.06743 -1.84005 0.2112 0.0341733 -0.804039 0.55475 +VERTEX_SE3:QUAT 286 -15.8287 2.91482 -2.78459 0.233965 0.0367539 -0.77984 0.579447 +VERTEX_SE3:QUAT 287 -16.2825 0.780701 -3.89242 0.260493 0.0342904 -0.758266 0.596657 +VERTEX_SE3:QUAT 288 -16.569 -1.28874 -5.12115 0.276355 0.0356411 -0.71388 0.642443 +VERTEX_SE3:QUAT 289 -16.6233 -3.29989 -6.21646 0.298437 0.0485984 -0.682433 0.665476 +VERTEX_SE3:QUAT 290 -16.3583 -5.35656 -7.56897 0.319558 0.0443096 -0.647297 0.690598 +VERTEX_SE3:QUAT 291 -15.9793 -7.28719 -8.73183 0.332371 0.047855 -0.61167 0.716309 +VERTEX_SE3:QUAT 292 -15.3007 -9.46021 -9.96591 0.343822 0.0465423 -0.569805 0.744945 +VERTEX_SE3:QUAT 293 -14.3701 -11.3972 -11.1049 0.354636 0.0475117 -0.52326 0.773418 +VERTEX_SE3:QUAT 294 -13.2443 -13.3355 -12.2088 0.372732 0.0368376 -0.464824 0.80228 +VERTEX_SE3:QUAT 295 -11.8221 -14.8259 -13.2932 0.384172 0.0482253 -0.427322 0.816996 +VERTEX_SE3:QUAT 296 -10.1877 -16.3851 -14.2961 0.403507 0.0502518 -0.378828 0.831352 +VERTEX_SE3:QUAT 297 -8.35478 -17.6882 -15.332 0.414838 0.0383404 -0.299835 0.858218 +VERTEX_SE3:QUAT 298 -6.29316 -18.8341 -16.1414 0.429356 0.0313433 -0.220853 0.875154 +VERTEX_SE3:QUAT 299 -4.04883 -19.6918 -16.5956 0.437061 0.0245036 -0.157378 0.885217 +VERTEX_SE3:QUAT 300 -1.40868 -20.2144 -17.2121 0.440837 0.026511 -0.114734 0.889829 +VERTEX_SE3:QUAT 301 1.028 -20.5783 -17.4919 0.448558 0.0344781 -0.0720304 0.890179 +VERTEX_SE3:QUAT 302 3.59264 -20.6627 -17.8502 0.451157 0.0198064 0.00874121 0.892182 +VERTEX_SE3:QUAT 303 6.06755 -20.4186 -17.8292 0.446274 0.0170402 0.0821913 0.890951 +VERTEX_SE3:QUAT 304 8.43516 -19.7847 -17.8028 0.444727 -0.000375564 0.180786 0.877231 +VERTEX_SE3:QUAT 305 10.891 -18.9722 -17.4182 0.437802 -0.0254623 0.266363 0.858331 +VERTEX_SE3:QUAT 306 13.1337 -17.6734 -16.8242 0.429389 -0.0234948 0.322509 0.843244 +VERTEX_SE3:QUAT 307 15.1099 -16.1931 -16.0067 0.411873 -0.0376303 0.385309 0.824913 +VERTEX_SE3:QUAT 308 16.7799 -14.4302 -15.0177 0.407052 -0.0313958 0.427481 0.806587 +VERTEX_SE3:QUAT 309 18.2922 -12.65 -13.9095 0.400762 -0.0218407 0.481224 0.779318 +VERTEX_SE3:QUAT 310 19.496 -10.6866 -12.8133 0.385433 -0.0298331 0.548206 0.741634 +VERTEX_SE3:QUAT 311 20.5558 -8.69157 -11.686 0.369218 -0.0119197 0.575859 0.72933 +VERTEX_SE3:QUAT 312 21.2057 -6.48778 -10.5383 0.365602 -0.00485963 0.602688 0.70928 +VERTEX_SE3:QUAT 313 21.8782 -4.25301 -9.41098 0.35441 -0.00646136 0.639657 0.682049 +VERTEX_SE3:QUAT 314 22.3112 -1.85686 -8.08375 0.335503 -0.000735212 0.678683 0.65332 +VERTEX_SE3:QUAT 315 22.4743 0.400379 -6.7997 0.315991 0.000318273 0.729616 0.606474 +VERTEX_SE3:QUAT 316 22.2824 2.72838 -5.73891 0.296989 0.00506057 0.771275 0.562945 +VERTEX_SE3:QUAT 317 21.7617 4.95236 -4.53054 0.271447 -8.68001e-05 0.804594 0.528152 +VERTEX_SE3:QUAT 318 21.115 7.04999 -3.42988 0.251039 -0.00621521 0.84859 0.465657 +VERTEX_SE3:QUAT 319 19.9381 9.17405 -2.48136 0.238003 -0.00931391 0.881539 0.407624 +VERTEX_SE3:QUAT 320 18.3488 11.0581 -1.37737 0.218933 -0.00288314 0.900124 0.376612 +VERTEX_SE3:QUAT 321 16.7739 12.962 -0.420522 0.205137 -0.0120552 0.931896 0.298903 +VERTEX_SE3:QUAT 322 14.8558 14.3398 0.510184 0.178584 -0.0152502 0.953396 0.242718 +VERTEX_SE3:QUAT 323 12.6276 15.3649 1.5224 0.144136 -0.0273335 0.969785 0.194922 +VERTEX_SE3:QUAT 324 10.1255 16.2851 2.1959 0.113594 -0.0282469 0.982009 0.148178 +VERTEX_SE3:QUAT 325 7.45744 16.9469 2.73942 0.0882872 -0.0307566 0.991564 0.089781 +VERTEX_SE3:QUAT 326 4.94611 17.2886 3.25522 0.0522989 -0.0324793 0.996561 0.0554679 +VERTEX_SE3:QUAT 327 2.20525 17.3521 3.4729 0.0406753 -0.0337587 0.997919 -0.0369361 +VERTEX_SE3:QUAT 328 -0.356399 16.8316 3.58116 0.0134806 -0.0377714 0.992639 -0.11428 +VERTEX_SE3:QUAT 329 -2.95908 16.0594 3.61033 -0.00764283 -0.0462688 0.986784 -0.155105 +VERTEX_SE3:QUAT 330 -5.51188 15.053 3.48475 -0.0335493 -0.0434115 0.981092 -0.185604 +VERTEX_SE3:QUAT 331 -8.11111 14.0593 3.09021 -0.0587634 -0.0372306 0.962713 -0.261428 +VERTEX_SE3:QUAT 332 -10.3999 12.7567 2.71419 -0.0852836 -0.0369253 0.94566 -0.311592 +VERTEX_SE3:QUAT 333 -12.427 11.1993 2.1799 -0.112961 -0.0402955 0.917347 -0.379592 +VERTEX_SE3:QUAT 334 -14.1635 9.30867 1.46136 -0.141649 -0.0517143 0.894708 -0.420427 +VERTEX_SE3:QUAT 335 -15.8442 7.13895 0.646049 -0.162489 -0.0500915 0.87568 -0.451965 +VERTEX_SE3:QUAT 336 -17.1742 5.06628 -0.289071 -0.187468 -0.0533328 0.841798 -0.503376 +VERTEX_SE3:QUAT 337 -18.1447 2.80796 -1.26039 -0.21664 -0.0639416 0.818758 -0.527839 +VERTEX_SE3:QUAT 338 -19.0345 0.343109 -2.41961 -0.24618 -0.0649214 0.771915 -0.582519 +VERTEX_SE3:QUAT 339 -19.587 -2.11484 -3.75344 -0.27546 -0.0610667 0.72124 -0.632618 +VERTEX_SE3:QUAT 340 -19.4734 -4.44656 -5.15809 -0.30138 -0.0670052 0.672797 -0.672327 +VERTEX_SE3:QUAT 341 -19.0393 -6.71914 -6.63954 -0.328394 -0.0696331 0.631263 -0.699153 +VERTEX_SE3:QUAT 342 -18.3263 -9.04121 -8.06944 -0.351348 -0.0752667 0.58021 -0.730921 +VERTEX_SE3:QUAT 343 -17.2894 -11.2696 -9.70821 -0.373578 -0.0778251 0.550843 -0.742263 +VERTEX_SE3:QUAT 344 -15.9761 -13.4957 -11.0136 -0.387096 -0.0708164 0.501925 -0.770203 +VERTEX_SE3:QUAT 345 -14.4596 -15.3663 -12.4455 -0.396393 -0.0817376 0.485903 -0.774655 +VERTEX_SE3:QUAT 346 -12.8714 -17.2003 -13.9374 -0.409379 -0.0752323 0.413176 -0.809959 +VERTEX_SE3:QUAT 347 -10.9296 -18.8805 -15.1765 -0.424762 -0.0638933 0.320853 -0.844126 +VERTEX_SE3:QUAT 348 -8.47838 -20.3356 -16.2226 -0.445863 -0.0644859 0.271791 -0.850398 +VERTEX_SE3:QUAT 349 -6.14299 -21.3828 -17.1323 -0.455393 -0.0635479 0.214394 -0.861751 +VERTEX_SE3:QUAT 350 -3.60342 -22.2346 -18.045 -0.457242 -0.0603676 0.155317 -0.873592 +VERTEX_SE3:QUAT 351 -0.883664 -22.8639 -18.7523 -0.464771 -0.0705222 0.117387 -0.874777 +VERTEX_SE3:QUAT 352 1.89085 -23.1965 -19.3065 -0.471989 -0.0629346 0.0423286 -0.878336 +VERTEX_SE3:QUAT 353 4.79431 -23.2413 -19.4957 -0.475515 -0.0514671 -0.0295628 -0.877703 +VERTEX_SE3:QUAT 354 7.78301 -22.7082 -19.7032 -0.475276 -0.0657581 -0.0684988 -0.874698 +VERTEX_SE3:QUAT 355 10.584 -22.2339 -19.6976 -0.477157 -0.0741194 -0.122541 -0.86707 +VERTEX_SE3:QUAT 356 13.2848 -21.3708 -19.8986 -0.472362 -0.0626426 -0.196629 -0.856906 +VERTEX_SE3:QUAT 357 15.8382 -19.8936 -19.714 -0.471596 -0.0242195 -0.312673 -0.824164 +VERTEX_SE3:QUAT 358 18.0736 -18.2542 -18.9894 -0.460221 -0.0167871 -0.394919 -0.794955 +VERTEX_SE3:QUAT 359 19.8042 -16.2493 -17.972 -0.450544 -0.0167187 -0.446867 -0.772684 +VERTEX_SE3:QUAT 360 21.5656 -14.2706 -16.8575 -0.437735 -0.00573284 -0.504595 -0.744137 +VERTEX_SE3:QUAT 361 22.9308 -12.0284 -15.5169 -0.428907 -0.00350584 -0.553655 -0.713787 +VERTEX_SE3:QUAT 362 23.868 -9.669 -14.1561 -0.405048 0.0133125 -0.611737 -0.679365 +VERTEX_SE3:QUAT 363 24.4259 -7.41819 -12.8284 -0.379212 0.010888 -0.660881 -0.647546 +VERTEX_SE3:QUAT 364 24.7754 -4.85706 -11.4748 -0.351042 0.00423494 -0.711284 -0.608955 +VERTEX_SE3:QUAT 365 24.545 -2.29686 -10.0744 -0.324696 0.00577119 -0.765303 -0.555744 +VERTEX_SE3:QUAT 366 23.9427 0.167018 -8.57304 -0.297905 0.00652652 -0.815949 -0.495416 +VERTEX_SE3:QUAT 367 22.7874 2.48035 -6.93252 -0.275523 0.00556607 -0.842018 -0.463748 +VERTEX_SE3:QUAT 368 21.6464 4.81279 -5.62905 -0.25511 0.00245934 -0.862558 -0.436928 +VERTEX_SE3:QUAT 369 20.1821 6.72458 -4.30264 -0.233932 -0.00206849 -0.900529 -0.366496 +VERTEX_SE3:QUAT 370 18.2748 8.62778 -3.05263 -0.21078 -0.00062352 -0.925584 -0.314429 +VERTEX_SE3:QUAT 371 16.0264 10.2517 -1.77006 -0.18593 -0.00113712 -0.946412 -0.264071 +VERTEX_SE3:QUAT 372 13.5835 11.6495 -1.07517 -0.150875 -0.00261765 -0.966716 -0.206614 +VERTEX_SE3:QUAT 373 10.7688 12.8334 -0.277676 -0.122469 0.000427247 -0.981297 -0.148516 +VERTEX_SE3:QUAT 374 7.9686 13.678 0.311098 -0.0870531 -0.0042304 -0.992318 -0.0877968 +VERTEX_SE3:QUAT 375 5.21447 14.0507 0.664892 -0.0610775 -0.00946392 -0.9971 -0.0444048 +VERTEX_SE3:QUAT 376 2.26418 14.2813 0.960018 -0.0209634 -0.00647047 -0.999559 -0.0199917 +VERTEX_SE3:QUAT 377 -0.644088 14.3012 1.0538 0.0122794 -0.00862189 -0.999882 -0.00341901 +VERTEX_SE3:QUAT 378 -3.50977 14.4611 0.999888 0.0394588 -0.00692586 -0.995895 0.0811677 +VERTEX_SE3:QUAT 379 -6.43813 13.9549 0.737631 0.0686731 -0.0146281 -0.984945 0.157964 +VERTEX_SE3:QUAT 380 -9.30591 12.9615 0.262946 0.0939278 -0.0141982 -0.96374 0.249362 +VERTEX_SE3:QUAT 381 -11.9443 11.3793 -0.180775 0.126206 -0.0117948 -0.946603 0.296439 +VERTEX_SE3:QUAT 382 -14.4243 9.58322 -0.977551 0.156163 -0.00690848 -0.93196 0.327134 +VERTEX_SE3:QUAT 383 -16.6385 7.74022 -1.92902 0.179927 -0.00221425 -0.918308 0.352607 +VERTEX_SE3:QUAT 384 -18.5767 5.65503 -3.21697 0.211677 -0.00115625 -0.885527 0.413563 +VERTEX_SE3:QUAT 385 -20.2643 3.28942 -4.52488 0.242408 -0.000888084 -0.858238 0.4524 +VERTEX_SE3:QUAT 386 -21.6699 0.853362 -5.87316 0.268934 -0.000463745 -0.813123 0.516241 +VERTEX_SE3:QUAT 387 -22.5702 -1.71481 -7.17225 0.291538 -0.00358442 -0.764361 0.575104 +VERTEX_SE3:QUAT 388 -22.8852 -4.57207 -8.60988 0.322507 -0.0150505 -0.724241 0.609293 +VERTEX_SE3:QUAT 389 -22.945 -7.24695 -10.1522 0.348164 -0.00336831 -0.696006 0.62797 +VERTEX_SE3:QUAT 390 -22.8051 -9.99496 -11.7704 0.368713 0.0150253 -0.665432 0.648865 +VERTEX_SE3:QUAT 391 -22.1821 -12.5403 -13.4781 0.394107 0.0162765 -0.621472 0.676895 +VERTEX_SE3:QUAT 392 -21.3073 -14.9132 -15.0532 0.409006 0.0251716 -0.574242 0.70875 +VERTEX_SE3:QUAT 393 -20.0299 -17.4207 -16.5937 0.43134 0.0319772 -0.540952 0.721314 +VERTEX_SE3:QUAT 394 -18.5388 -19.8916 -18.2136 0.4528 0.0348798 -0.490403 0.743815 +VERTEX_SE3:QUAT 395 -16.753 -21.9652 -19.695 0.471773 0.0400111 -0.452647 0.755606 +VERTEX_SE3:QUAT 396 -14.8472 -23.7491 -21.2353 0.492489 0.0278993 -0.380936 0.782026 +VERTEX_SE3:QUAT 397 -12.5869 -25.5955 -22.5007 0.512134 0.0299135 -0.3306 0.792166 +VERTEX_SE3:QUAT 398 -10.1378 -27.1204 -23.5641 0.526314 0.0228371 -0.252754 0.811534 +VERTEX_SE3:QUAT 399 -7.285 -28.2003 -24.5179 0.532759 0.023822 -0.190217 0.824268 +VERTEX_SE3:QUAT 400 -4.22314 -28.9216 -25.2414 0.534701 0.0189832 -0.127152 0.835205 +VERTEX_SE3:QUAT 401 -1.04381 -29.3961 -25.8899 0.537981 0.0128173 -0.0551263 0.841055 +VERTEX_SE3:QUAT 402 2.12791 -29.3846 -26.0314 0.539979 -0.000253073 0.0110925 0.841605 +VERTEX_SE3:QUAT 403 5.36041 -29.2555 -26.0555 0.546262 -0.0224029 0.085502 0.832938 +VERTEX_SE3:QUAT 404 8.52676 -28.7514 -25.7026 0.533182 -0.0273665 0.154807 0.831266 +VERTEX_SE3:QUAT 405 11.4389 -27.7141 -25.1211 0.52067 -0.0246041 0.228594 0.822218 +VERTEX_SE3:QUAT 406 14.38 -26.4 -24.297 0.507848 -0.037508 0.302821 0.805594 +VERTEX_SE3:QUAT 407 17.1244 -24.8998 -22.9854 0.500105 -0.0190954 0.333853 0.798794 +VERTEX_SE3:QUAT 408 19.5526 -23.1371 -21.695 0.486724 -0.00520101 0.37517 0.788873 +VERTEX_SE3:QUAT 409 21.8522 -21.1787 -20.3216 0.480986 -0.00161642 0.407923 0.776047 +VERTEX_SE3:QUAT 410 23.7446 -19.089 -18.9438 0.469175 0.0219935 0.439392 0.765719 +VERTEX_SE3:QUAT 411 25.7598 -16.693 -17.6871 0.459015 0.0312437 0.47236 0.751801 +VERTEX_SE3:QUAT 412 27.5417 -14.0359 -16.4819 0.442154 0.0356272 0.510151 0.73687 +VERTEX_SE3:QUAT 413 28.9569 -11.444 -15.1833 0.415347 0.0695614 0.528228 0.737308 +VERTEX_SE3:QUAT 414 30.3792 -8.72845 -14.0504 0.396954 0.063939 0.609696 0.683089 +VERTEX_SE3:QUAT 415 31.0926 -5.90838 -12.7822 0.384714 0.0660715 0.663519 0.638258 +VERTEX_SE3:QUAT 416 31.3269 -2.91618 -11.3839 0.368754 0.0623361 0.713712 0.592241 +VERTEX_SE3:QUAT 417 31.1632 -0.018385 -9.94283 0.344266 0.060607 0.764988 0.540926 +VERTEX_SE3:QUAT 418 30.4227 2.79543 -8.45588 0.327558 0.0561944 0.806987 0.48818 +VERTEX_SE3:QUAT 419 29.2517 5.33575 -6.85679 0.303039 0.0642892 0.832758 0.458857 +VERTEX_SE3:QUAT 420 27.8814 8.06552 -5.47442 0.269478 0.0580077 0.877061 0.393423 +VERTEX_SE3:QUAT 421 25.9429 10.3727 -3.9882 0.245167 0.0613656 0.90009 0.354916 +VERTEX_SE3:QUAT 422 23.583 12.5201 -2.73929 0.221826 0.0713533 0.916423 0.325377 +VERTEX_SE3:QUAT 423 21.0853 14.7981 -1.59389 0.197548 0.0744188 0.938161 0.274391 +VERTEX_SE3:QUAT 424 18.3503 16.5394 -0.567776 0.173791 0.070189 0.955976 0.225786 +VERTEX_SE3:QUAT 425 15.6815 18.0326 0.424799 0.144819 0.0691949 0.96959 0.184754 +VERTEX_SE3:QUAT 426 12.7034 19.3271 1.06419 0.112026 0.0690843 0.98026 0.147537 +VERTEX_SE3:QUAT 427 9.57928 20.1887 1.50992 0.0892794 0.0595084 0.992095 0.0650834 +VERTEX_SE3:QUAT 428 6.20862 20.4894 1.80133 0.0584874 0.058142 0.996131 -0.0303673 +VERTEX_SE3:QUAT 429 2.89736 20.3484 2.02209 0.0302076 0.0474146 0.992027 -0.112792 +VERTEX_SE3:QUAT 430 -0.328092 19.5012 2.16141 -0.00117423 0.0418846 0.984463 -0.170521 +VERTEX_SE3:QUAT 431 -3.45515 18.272 2.00458 -0.0410535 0.0362919 0.973489 -0.222073 +VERTEX_SE3:QUAT 432 -6.31935 16.6525 1.70542 -0.0765992 0.0307023 0.956267 -0.280613 +VERTEX_SE3:QUAT 433 -8.97498 14.4926 1.12648 -0.111034 0.0268227 0.944794 -0.307109 +VERTEX_SE3:QUAT 434 -11.4956 12.4148 0.476862 -0.147526 0.0264107 0.918273 -0.366487 +VERTEX_SE3:QUAT 435 -13.6071 10.0945 -0.50134 -0.185413 0.0231217 0.901625 -0.390076 +VERTEX_SE3:QUAT 436 -15.7123 7.42249 -1.57896 -0.215113 0.0247864 0.858617 -0.464638 +VERTEX_SE3:QUAT 437 -17.1373 4.83306 -2.83182 -0.250484 0.0174811 0.828371 -0.500753 +VERTEX_SE3:QUAT 438 -18.1423 1.92867 -4.30279 -0.278147 0.00323061 0.79748 -0.535396 +VERTEX_SE3:QUAT 439 -19.0168 -0.720246 -5.83885 -0.293082 0.00512649 0.76096 -0.578806 +VERTEX_SE3:QUAT 440 -19.3418 -3.81883 -7.54758 -0.312583 0.0101995 0.704044 -0.637582 +VERTEX_SE3:QUAT 441 -19.3144 -6.83507 -9.0948 -0.338737 0.0112494 0.651427 -0.678803 +VERTEX_SE3:QUAT 442 -18.6639 -9.72356 -10.5113 -0.359948 -0.00667018 0.620238 -0.69692 +VERTEX_SE3:QUAT 443 -17.7392 -12.5959 -12.4523 -0.38435 -0.0112677 0.563728 -0.730998 +VERTEX_SE3:QUAT 444 -16.2933 -15.4583 -14.1539 -0.412437 -0.0137081 0.508668 -0.755622 +VERTEX_SE3:QUAT 445 -14.5483 -17.8856 -15.6122 -0.441477 -0.015782 0.446542 -0.778106 +VERTEX_SE3:QUAT 446 -12.314 -20.236 -17.0378 -0.456659 -0.0139929 0.383741 -0.802502 +VERTEX_SE3:QUAT 447 -9.77787 -22.3741 -18.397 -0.476546 -0.0109953 0.321217 -0.818293 +VERTEX_SE3:QUAT 448 -6.91983 -24.0526 -19.4178 -0.486766 0.0011626 0.240849 -0.839672 +VERTEX_SE3:QUAT 449 -3.65182 -25.2594 -20.1737 -0.490632 0.000107808 0.193128 -0.849695 +VERTEX_SE3:QUAT 450 -0.290828 -26.2999 -20.8484 -0.502108 -0.0115339 0.143476 -0.852742 +VERTEX_SE3:QUAT 451 2.94644 -27.1122 -21.2384 -0.508131 -0.00358958 0.0711987 -0.858325 +VERTEX_SE3:QUAT 452 6.55644 -27.3056 -21.4427 -0.50938 -0.00650872 0.00963406 -0.860463 +VERTEX_SE3:QUAT 453 10.1313 -27.249 -21.486 -0.508906 -0.0196238 -0.055268 -0.858822 +VERTEX_SE3:QUAT 454 13.5545 -26.6069 -21.4095 -0.508933 -0.027092 -0.127607 -0.850864 +VERTEX_SE3:QUAT 455 17.0353 -25.6896 -21.0473 -0.508297 -0.029818 -0.193801 -0.838562 +VERTEX_SE3:QUAT 456 20.1391 -24.2857 -20.4397 -0.505348 -0.0486752 -0.244046 -0.826254 +VERTEX_SE3:QUAT 457 23.2506 -22.2215 -19.8 -0.496338 -0.0373578 -0.336076 -0.799566 +VERTEX_SE3:QUAT 458 25.8099 -20.1833 -18.7058 -0.481336 -0.0212322 -0.430124 -0.763451 +VERTEX_SE3:QUAT 459 28.0144 -17.8257 -17.2606 -0.462957 -0.0364466 -0.464687 -0.753929 +VERTEX_SE3:QUAT 460 29.8231 -14.9523 -15.9914 -0.446021 -0.0312302 -0.524918 -0.724259 +VERTEX_SE3:QUAT 461 31.1216 -12.1902 -14.5019 -0.42069 -0.0382292 -0.588473 -0.68939 +VERTEX_SE3:QUAT 462 31.9247 -9.14275 -12.9197 -0.401232 -0.0286921 -0.657117 -0.637485 +VERTEX_SE3:QUAT 463 32.1911 -6.03668 -11.2164 -0.376403 -0.0297114 -0.704741 -0.600648 +VERTEX_SE3:QUAT 464 31.9149 -2.86901 -9.60832 -0.346338 -0.0439564 -0.735013 -0.581269 +VERTEX_SE3:QUAT 465 31.4161 0.395615 -8.08792 -0.324937 -0.0407196 -0.783741 -0.527739 +VERTEX_SE3:QUAT 466 30.4936 3.59569 -6.66653 -0.306781 -0.039102 -0.828817 -0.466281 +VERTEX_SE3:QUAT 467 28.9618 6.35729 -4.93146 -0.290265 -0.0275443 -0.868506 -0.400856 +VERTEX_SE3:QUAT 468 26.9804 8.80441 -3.25136 -0.255766 -0.0287821 -0.902455 -0.345442 +VERTEX_SE3:QUAT 469 24.7749 11.1052 -1.69453 -0.226467 -0.0135793 -0.934086 -0.275703 +VERTEX_SE3:QUAT 470 22.058 12.9404 -0.0985097 -0.197606 -0.0153592 -0.951195 -0.236523 +VERTEX_SE3:QUAT 471 18.9062 14.4898 1.09077 -0.159936 -0.0186788 -0.968655 -0.189155 +VERTEX_SE3:QUAT 472 15.7205 15.6265 2.00752 -0.119448 -0.019031 -0.985864 -0.115937 +VERTEX_SE3:QUAT 473 12.2229 16.4189 2.58922 -0.0840685 -0.0224249 -0.993458 -0.0739621 +VERTEX_SE3:QUAT 474 8.56144 16.7854 3.11816 -0.0434743 -0.0194853 -0.99884 0.00703945 +VERTEX_SE3:QUAT 475 4.82569 16.6787 3.35551 -0.0102928 -0.0236542 -0.996567 0.0786625 +VERTEX_SE3:QUAT 476 1.25729 16.2147 3.42296 0.0292417 -0.0246297 -0.993018 0.111592 +VERTEX_SE3:QUAT 477 -2.2859 15.2729 3.13618 0.0640625 -0.0167974 -0.988163 0.138373 +VERTEX_SE3:QUAT 478 -5.67293 14.0999 2.52998 0.0974722 -0.0154605 -0.977252 0.187722 +VERTEX_SE3:QUAT 479 -8.89246 12.5955 1.51122 0.136609 -0.0164887 -0.960409 0.242242 +VERTEX_SE3:QUAT 480 -11.7742 10.7307 0.357529 0.165125 -0.017052 -0.938316 0.303325 +VERTEX_SE3:QUAT 481 -14.4245 8.60774 -1.0292 0.198025 -0.0150663 -0.912205 0.358387 +VERTEX_SE3:QUAT 482 -16.913 5.99385 -2.41924 0.230784 -0.0125233 -0.880362 0.414179 +VERTEX_SE3:QUAT 483 -18.7091 3.22184 -3.99529 0.25508 -0.00320629 -0.853957 0.453521 +VERTEX_SE3:QUAT 484 -20.2185 0.373774 -5.8305 0.280207 0.00664535 -0.829287 0.483448 +VERTEX_SE3:QUAT 485 -21.3281 -2.6405 -7.52378 0.310983 0.0120836 -0.801493 0.510639 +VERTEX_SE3:QUAT 486 -22.0882 -5.80943 -9.45014 0.345952 0.0220674 -0.755134 0.556419 +VERTEX_SE3:QUAT 487 -22.3876 -8.88341 -11.5095 0.377214 0.0330651 -0.704705 0.600006 +VERTEX_SE3:QUAT 488 -22.082 -12.0471 -13.6967 0.410395 0.0463312 -0.662255 0.625178 +VERTEX_SE3:QUAT 489 -21.595 -15.0229 -15.9905 0.435047 0.043414 -0.598021 0.671729 +VERTEX_SE3:QUAT 490 -20.287 -17.8955 -18.2646 0.457504 0.0313101 -0.518736 0.721542 +VERTEX_SE3:QUAT 491 -18.43 -20.4946 -20.2511 0.474676 0.0525547 -0.503991 0.719663 +VERTEX_SE3:QUAT 492 -16.5788 -22.8602 -22.5498 0.492699 0.0576667 -0.458623 0.737283 +VERTEX_SE3:QUAT 493 -14.4025 -24.9608 -24.4881 0.520801 0.052099 -0.399865 0.752436 +VERTEX_SE3:QUAT 494 -11.7336 -26.8488 -26.4819 0.534267 0.0463281 -0.350503 0.767828 +VERTEX_SE3:QUAT 495 -8.68537 -28.5044 -28.1084 0.552022 0.0361424 -0.275197 0.786277 +VERTEX_SE3:QUAT 496 -5.42294 -29.8933 -29.3769 0.556241 0.0224632 -0.194176 0.807705 +VERTEX_SE3:QUAT 497 -1.8603 -30.6192 -30.2887 0.56271 0.0132618 -0.122618 0.817402 +VERTEX_SE3:QUAT 498 1.92265 -31.0791 -30.8495 0.558405 0.00998093 -0.0515899 0.827903 +VERTEX_SE3:QUAT 499 5.71204 -31.2509 -31.0877 0.560371 0.0293959 -0.0217415 0.827434 +VERTEX_SE3:QUAT 500 9.53393 -30.9988 -31.3911 0.565851 0.0399206 0.0356168 0.82277 +VERTEX_SE3:QUAT 501 13.3751 -30.6687 -31.3138 0.557702 0.0209916 0.141029 0.817703 +VERTEX_SE3:QUAT 502 17.1054 -29.5648 -30.8212 0.544641 0.0083661 0.231734 0.805975 +VERTEX_SE3:QUAT 503 20.5001 -27.6796 -29.8375 0.540543 0.0102541 0.308998 0.78245 +VERTEX_SE3:QUAT 504 23.4133 -25.6736 -28.6238 0.527024 0.0211029 0.359537 0.769762 +VERTEX_SE3:QUAT 505 26.0647 -23.233 -27.43 0.516718 0.0311778 0.412407 0.749634 +VERTEX_SE3:QUAT 506 28.3687 -20.6485 -26.0952 0.49915 0.0253372 0.479121 0.721561 +VERTEX_SE3:QUAT 507 30.4304 -17.7794 -24.4143 0.485612 0.0464439 0.534853 0.689895 +VERTEX_SE3:QUAT 508 31.9679 -14.6739 -22.4479 0.471629 0.0681749 0.568207 0.670865 +VERTEX_SE3:QUAT 509 33.2418 -11.3347 -20.7157 0.455879 0.0666848 0.618687 0.63636 +VERTEX_SE3:QUAT 510 34.0935 -8.02531 -19.0067 0.432203 0.0605933 0.672952 0.597214 +VERTEX_SE3:QUAT 511 34.3214 -4.62132 -17.0729 0.411333 0.0745668 0.703357 0.574921 +VERTEX_SE3:QUAT 512 34.1569 -1.12579 -15.3516 0.39255 0.0734325 0.741105 0.539699 +VERTEX_SE3:QUAT 513 33.597 2.21001 -13.5289 0.362284 0.0929735 0.770163 0.516677 +VERTEX_SE3:QUAT 514 32.5695 5.39453 -11.8845 0.330697 0.103936 0.800692 0.488599 +VERTEX_SE3:QUAT 515 31.3769 8.69692 -10.1986 0.306542 0.105957 0.828202 0.457041 +VERTEX_SE3:QUAT 516 29.7204 11.9313 -8.63749 0.274434 0.102315 0.86772 0.401596 +VERTEX_SE3:QUAT 517 27.4607 14.8785 -7.19319 0.237155 0.101036 0.901767 0.346937 +VERTEX_SE3:QUAT 518 24.671 17.5029 -5.97366 0.204422 0.118512 0.915072 0.326818 +VERTEX_SE3:QUAT 519 21.8262 20.0044 -4.94002 0.169837 0.125267 0.939601 0.269469 +VERTEX_SE3:QUAT 520 18.6812 22.0672 -3.99766 0.141269 0.130737 0.955668 0.222824 +VERTEX_SE3:QUAT 521 15.2436 23.6969 -3.22841 0.119239 0.126871 0.974121 0.144133 +VERTEX_SE3:QUAT 522 11.5308 24.7764 -2.48995 0.0793227 0.120291 0.987988 0.0558303 +VERTEX_SE3:QUAT 523 7.62441 25.319 -2.13606 0.0426024 0.116855 0.991861 0.0272433 +VERTEX_SE3:QUAT 524 3.75263 25.3396 -1.78869 0.009306 0.111053 0.993277 -0.0313212 +VERTEX_SE3:QUAT 525 -0.186675 25.0221 -1.73135 -0.0275975 0.114233 0.989646 -0.0824011 +VERTEX_SE3:QUAT 526 -3.90639 24.1983 -1.86365 -0.0604432 0.118017 0.983818 -0.120502 +VERTEX_SE3:QUAT 527 -7.57216 22.9915 -2.26296 -0.0934146 0.114022 0.968354 -0.201405 +VERTEX_SE3:QUAT 528 -11.0392 21.1883 -2.95114 -0.126179 0.111692 0.961282 -0.218038 +VERTEX_SE3:QUAT 529 -14.4134 19.2654 -3.64702 -0.160887 0.0982236 0.949115 -0.252287 +VERTEX_SE3:QUAT 530 -17.6343 16.8676 -4.80088 -0.202579 0.0900115 0.933393 -0.282199 +VERTEX_SE3:QUAT 531 -20.5801 14.5491 -6.15166 -0.235088 0.0868415 0.915658 -0.314265 +VERTEX_SE3:QUAT 532 -23.3265 11.953 -7.68787 -0.262148 0.0829742 0.88871 -0.366862 +VERTEX_SE3:QUAT 533 -25.5388 8.84525 -9.40173 -0.284655 0.0838938 0.854946 -0.425443 +VERTEX_SE3:QUAT 534 -27.3444 5.57616 -11.016 -0.316621 0.0856747 0.805403 -0.493697 +VERTEX_SE3:QUAT 535 -28.3247 2.12694 -12.6279 -0.345491 0.0709534 0.77774 -0.52031 +VERTEX_SE3:QUAT 536 -29.0001 -1.30159 -14.5624 -0.373567 0.0738588 0.725311 -0.573512 +VERTEX_SE3:QUAT 537 -29.083 -4.70009 -16.3726 -0.397135 0.0674417 0.685144 -0.606888 +VERTEX_SE3:QUAT 538 -28.6072 -8.21968 -18.4748 -0.417108 0.0608269 0.65485 -0.62729 +VERTEX_SE3:QUAT 539 -27.9906 -11.5836 -20.5436 -0.443357 0.046952 0.615792 -0.649639 +VERTEX_SE3:QUAT 540 -26.9258 -14.9421 -22.5688 -0.459393 0.0469039 0.546415 -0.698705 +VERTEX_SE3:QUAT 541 -25.1794 -18.1875 -24.3008 -0.482283 0.0438223 0.480312 -0.731289 +VERTEX_SE3:QUAT 542 -22.9383 -21.3392 -25.8093 -0.491853 0.0262886 0.428337 -0.757573 +VERTEX_SE3:QUAT 543 -20.3587 -24.0693 -27.4442 -0.503813 0.0287442 0.357238 -0.785956 +VERTEX_SE3:QUAT 544 -17.2257 -26.398 -28.6519 -0.509992 0.0185105 0.309208 -0.802469 +VERTEX_SE3:QUAT 545 -13.8864 -28.4268 -29.8276 -0.517456 0.00633322 0.261643 -0.814704 +VERTEX_SE3:QUAT 546 -10.445 -30.0779 -30.7705 -0.525003 0.00140186 0.204378 -0.826196 +VERTEX_SE3:QUAT 547 -6.72197 -31.2563 -31.5699 -0.535223 -0.0198093 0.157797 -0.829605 +VERTEX_SE3:QUAT 548 -2.72749 -32.0197 -32.6401 -0.536305 -0.0163978 0.0711554 -0.84086 +VERTEX_SE3:QUAT 549 1.41086 -32.3423 -32.7849 -0.540152 -0.01829 -0.000911866 -0.841368 +VERTEX_SE3:QUAT 550 5.55165 -32.2164 -32.79 -0.547374 -0.0443352 -0.0360551 -0.834935 +VERTEX_SE3:QUAT 551 9.78684 -31.53 -32.8891 -0.546797 -0.0596279 -0.0922015 -0.830034 +VERTEX_SE3:QUAT 552 13.6092 -30.4832 -32.8204 -0.551587 -0.0709654 -0.142376 -0.818807 +VERTEX_SE3:QUAT 553 17.5427 -29.1855 -32.429 -0.547357 -0.0708159 -0.221141 -0.804041 +VERTEX_SE3:QUAT 554 21.0132 -27.1895 -31.8189 -0.542957 -0.0775779 -0.284689 -0.786213 +VERTEX_SE3:QUAT 555 24.3989 -24.5385 -31.131 -0.528343 -0.104053 -0.332841 -0.774108 +VERTEX_SE3:QUAT 556 27.4878 -21.8709 -30.4094 -0.518522 -0.114627 -0.373594 -0.760541 +VERTEX_SE3:QUAT 557 30.058 -18.8263 -29.4181 -0.51114 -0.125292 -0.418958 -0.73994 +VERTEX_SE3:QUAT 558 32.417 -15.5076 -28.2922 -0.495655 -0.145507 -0.459673 -0.722395 +VERTEX_SE3:QUAT 559 34.53 -12.193 -27.1909 -0.477733 -0.155753 -0.529167 -0.683735 +VERTEX_SE3:QUAT 560 35.9531 -8.48772 -26.0183 -0.458176 -0.187934 -0.56256 -0.662029 +VERTEX_SE3:QUAT 561 37.0545 -4.50029 -24.9069 -0.437715 -0.180941 -0.624807 -0.620711 +VERTEX_SE3:QUAT 562 37.5379 -0.634645 -23.4985 -0.418801 -0.185721 -0.670843 -0.583167 +VERTEX_SE3:QUAT 563 37.3946 3.33985 -22.2427 -0.39181 -0.199075 -0.710382 -0.549737 +VERTEX_SE3:QUAT 564 36.7361 7.05332 -20.858 -0.363041 -0.197173 -0.754649 -0.509735 +VERTEX_SE3:QUAT 565 35.654 10.9193 -19.4902 -0.35076 -0.199867 -0.794393 -0.453828 +VERTEX_SE3:QUAT 566 34.0104 14.4182 -18.0479 -0.326192 -0.207581 -0.821488 -0.419125 +VERTEX_SE3:QUAT 567 31.9239 17.6767 -16.6638 -0.30161 -0.214961 -0.844992 -0.385761 +VERTEX_SE3:QUAT 568 29.4002 20.9804 -15.3856 -0.275046 -0.215444 -0.878545 -0.325717 +VERTEX_SE3:QUAT 569 26.5185 23.8949 -14.0119 -0.245376 -0.221647 -0.909035 -0.253609 +VERTEX_SE3:QUAT 570 23.2236 26.1042 -12.7104 -0.211686 -0.234071 -0.922961 -0.220323 +VERTEX_SE3:QUAT 571 19.6615 28.0459 -11.6733 -0.188155 -0.226471 -0.941374 -0.164693 +VERTEX_SE3:QUAT 572 15.8787 29.6088 -10.6592 -0.160216 -0.222481 -0.954764 -0.115152 +VERTEX_SE3:QUAT 573 12.113 30.6347 -9.85806 -0.129211 -0.22556 -0.962021 -0.0833245 +VERTEX_SE3:QUAT 574 8.05018 31.4756 -9.11121 -0.103127 -0.212082 -0.971692 -0.0141982 +VERTEX_SE3:QUAT 575 3.57887 31.6348 -8.39215 -0.0777807 -0.208401 -0.974293 0.0356698 +VERTEX_SE3:QUAT 576 -0.563339 31.2532 -7.75985 -0.0386935 -0.2117 -0.973426 0.0782832 +VERTEX_SE3:QUAT 577 -4.94059 30.4033 -7.4885 -0.00648757 -0.211081 -0.968185 0.134241 +VERTEX_SE3:QUAT 578 -9.24206 29.0997 -7.30306 0.0231107 -0.214243 -0.959895 0.179353 +VERTEX_SE3:QUAT 579 -13.1744 27.3496 -7.36974 0.0631761 -0.204107 -0.958644 0.188016 +VERTEX_SE3:QUAT 580 -16.9305 25.7343 -7.71152 0.0912304 -0.205064 -0.942346 0.248213 +VERTEX_SE3:QUAT 581 -20.6961 23.2185 -8.05191 0.128061 -0.202215 -0.926712 0.28968 +VERTEX_SE3:QUAT 582 -23.9504 20.4869 -8.57084 0.165746 -0.196915 -0.905106 0.338431 +VERTEX_SE3:QUAT 583 -26.749 17.3919 -9.35835 0.197938 -0.196886 -0.86877 0.409017 +VERTEX_SE3:QUAT 584 -28.9825 13.8694 -10.2813 0.236726 -0.19259 -0.839639 0.449306 +VERTEX_SE3:QUAT 585 -30.831 10.0697 -11.3859 0.265459 -0.182336 -0.806836 0.495279 +VERTEX_SE3:QUAT 586 -32.2181 5.97961 -12.5423 0.284218 -0.167995 -0.757181 0.563626 +VERTEX_SE3:QUAT 587 -32.9918 1.77843 -13.5665 0.313128 -0.158647 -0.732547 0.58323 +VERTEX_SE3:QUAT 588 -33.3297 -2.29283 -14.8295 0.341576 -0.152734 -0.686156 0.623849 +VERTEX_SE3:QUAT 589 -33.2651 -6.43611 -16.0303 0.364171 -0.134976 -0.648916 0.654269 +VERTEX_SE3:QUAT 590 -32.7256 -10.3598 -17.3036 0.386445 -0.130263 -0.602474 0.686088 +VERTEX_SE3:QUAT 591 -31.4422 -14.0573 -18.5069 0.412164 -0.132469 -0.517935 0.737778 +VERTEX_SE3:QUAT 592 -29.2457 -17.7012 -19.444 0.426066 -0.125552 -0.461068 0.768193 +VERTEX_SE3:QUAT 593 -26.5981 -20.8813 -20.2799 0.452799 -0.100085 -0.420266 0.779956 +VERTEX_SE3:QUAT 594 -23.7794 -24.0075 -21.2237 0.464297 -0.0899815 -0.350019 0.808591 +VERTEX_SE3:QUAT 595 -20.4301 -26.6194 -22.1045 0.471459 -0.0790635 -0.288835 0.829488 +VERTEX_SE3:QUAT 596 -16.903 -28.9161 -22.6602 0.479839 -0.0589121 -0.238192 0.842347 +VERTEX_SE3:QUAT 597 -12.9328 -30.732 -22.7753 0.494185 -0.0393887 -0.171811 0.8513 +VERTEX_SE3:QUAT 598 -8.66442 -32.0716 -23.2033 0.501351 -0.019046 -0.118192 0.856922 +VERTEX_SE3:QUAT 599 -4.29892 -33.0918 -23.6286 0.511232 0.00216287 -0.0599165 0.857349 +VERTEX_SE3:QUAT 600 0.20397 -33.0689 -23.8227 0.519616 0.0227234 -0.0072735 0.854067 +VERTEX_SE3:QUAT 601 4.56467 -32.8446 -24.0824 0.516457 0.0496382 0.0494881 0.85344 +VERTEX_SE3:QUAT 602 8.77187 -31.9202 -24.0909 0.509065 0.0710468 0.110794 0.850606 +VERTEX_SE3:QUAT 603 12.8907 -30.5915 -24.1223 0.511301 0.0785179 0.192212 0.833943 +VERTEX_SE3:QUAT 604 17.0304 -28.6633 -23.8747 0.515134 0.0934243 0.238447 0.817956 +VERTEX_SE3:QUAT 605 20.6309 -26.2939 -23.502 0.516717 0.102193 0.29921 0.795634 +VERTEX_SE3:QUAT 606 24.0753 -23.4819 -22.9262 0.500673 0.101281 0.371421 0.775316 +VERTEX_SE3:QUAT 607 26.9022 -20.2486 -21.9915 0.485965 0.0956707 0.45243 0.741615 +VERTEX_SE3:QUAT 608 29.1574 -16.6933 -20.4832 0.469482 0.108908 0.515851 0.708254 +VERTEX_SE3:QUAT 609 30.9107 -12.8305 -18.9135 0.456067 0.119032 0.57332 0.670178 +VERTEX_SE3:QUAT 610 32.118 -8.87011 -17.2923 0.437594 0.130511 0.621523 0.636544 +VERTEX_SE3:QUAT 611 32.7159 -4.7842 -15.6439 0.411083 0.149863 0.660664 0.60998 +VERTEX_SE3:QUAT 612 32.9774 -0.584054 -14.1729 0.38249 0.173239 0.690251 0.589273 +VERTEX_SE3:QUAT 613 32.626 3.70169 -12.676 0.351309 0.191018 0.729901 0.554382 +VERTEX_SE3:QUAT 614 31.6032 7.81401 -11.3948 0.327349 0.19599 0.765864 0.517574 +VERTEX_SE3:QUAT 615 30.3265 11.8199 -10.121 0.307508 0.190826 0.808593 0.463898 +VERTEX_SE3:QUAT 616 28.5466 15.5855 -8.84703 0.276112 0.194867 0.845573 0.413273 +VERTEX_SE3:QUAT 617 26.1208 19.0413 -7.50158 0.252307 0.194916 0.867375 0.382113 +VERTEX_SE3:QUAT 618 23.1834 22.356 -6.14712 0.211904 0.211401 0.880639 0.367262 +VERTEX_SE3:QUAT 619 20.1424 25.5065 -5.10119 0.180521 0.220969 0.896721 0.338343 +VERTEX_SE3:QUAT 620 16.729 28.2649 -4.32449 0.145496 0.23452 0.905952 0.321065 +VERTEX_SE3:QUAT 621 13.2454 30.9051 -3.8224 0.111611 0.241673 0.927321 0.263081 +VERTEX_SE3:QUAT 622 9.4836 33.1443 -3.50115 0.0735662 0.253766 0.940442 0.213913 +VERTEX_SE3:QUAT 623 5.54983 34.9186 -3.27773 0.0369189 0.25144 0.957953 0.133193 +VERTEX_SE3:QUAT 624 1.1928 35.9144 -3.06707 0.00860437 0.25325 0.964665 0.0721977 +VERTEX_SE3:QUAT 625 -3.3171 36.5125 -3.17149 -0.0221538 0.248711 0.968255 0.0115596 +VERTEX_SE3:QUAT 626 -7.91389 36.2736 -3.57108 -0.0449363 0.252242 0.96508 -0.0545498 +VERTEX_SE3:QUAT 627 -12.4225 35.5296 -4.03622 -0.0813076 0.24972 0.956591 -0.126344 +VERTEX_SE3:QUAT 628 -16.7553 34.1302 -4.4118 -0.105256 0.240608 0.944681 -0.196487 +VERTEX_SE3:QUAT 629 -20.7729 31.951 -4.89366 -0.137605 0.229512 0.936074 -0.228374 +VERTEX_SE3:QUAT 630 -24.6367 29.4252 -5.83689 -0.165844 0.216597 0.924222 -0.267198 +VERTEX_SE3:QUAT 631 -28.2306 26.7544 -6.84726 -0.199178 0.214277 0.909396 -0.295657 +VERTEX_SE3:QUAT 632 -31.2993 23.7364 -7.96458 -0.226571 0.199155 0.88094 -0.364619 +VERTEX_SE3:QUAT 633 -33.9217 20.0407 -9.18318 -0.252185 0.190101 0.856303 -0.408668 +VERTEX_SE3:QUAT 634 -36.2203 16.1967 -10.6742 -0.276104 0.180505 0.832196 -0.445684 +VERTEX_SE3:QUAT 635 -38.0019 12.1883 -12.0622 -0.306435 0.169696 0.805205 -0.478483 +VERTEX_SE3:QUAT 636 -39.2673 8.15256 -13.6716 -0.337946 0.152727 0.780095 -0.503903 +VERTEX_SE3:QUAT 637 -40.3017 3.86773 -15.3081 -0.366712 0.144781 0.735887 -0.550483 +VERTEX_SE3:QUAT 638 -40.5755 -0.305127 -17.2152 -0.392257 0.131823 0.696053 -0.586743 +VERTEX_SE3:QUAT 639 -40.485 -4.47524 -18.969 -0.42366 0.132407 0.641561 -0.625603 +VERTEX_SE3:QUAT 640 -39.5462 -8.5585 -20.7407 -0.457973 0.101837 0.615476 -0.633308 +VERTEX_SE3:QUAT 641 -38.2086 -12.5333 -22.7047 -0.477593 0.0864701 0.574162 -0.659367 +VERTEX_SE3:QUAT 642 -36.5896 -16.3633 -24.6303 -0.490755 0.0884537 0.496737 -0.710344 +VERTEX_SE3:QUAT 643 -34.2656 -19.8835 -26.351 -0.512634 0.0737122 0.448309 -0.728554 +VERTEX_SE3:QUAT 644 -31.273 -23.0372 -27.8042 -0.525572 0.0696137 0.379751 -0.758101 +VERTEX_SE3:QUAT 645 -27.8092 -25.8798 -29.2191 -0.540335 0.0583581 0.317236 -0.77717 +VERTEX_SE3:QUAT 646 -23.997 -28.0451 -30.2312 -0.551822 0.0334898 0.263859 -0.790411 +VERTEX_SE3:QUAT 647 -19.869 -29.817 -31.1509 -0.562134 0.00553005 0.228528 -0.794827 +VERTEX_SE3:QUAT 648 -15.6206 -31.2662 -32.2668 -0.564805 -0.000771616 0.156198 -0.810307 +VERTEX_SE3:QUAT 649 -11.2226 -32.188 -33.2507 -0.569083 0.00215178 0.0752124 -0.81883 +VERTEX_SE3:QUAT 650 -6.63959 -32.5115 -33.5085 -0.574589 -0.010357 0.0131485 -0.818271 +VERTEX_SE3:QUAT 651 -2.02021 -32.1239 -33.4816 -0.571937 -0.0191989 -0.0580249 -0.818018 +VERTEX_SE3:QUAT 652 2.4852 -31.2014 -33.2399 -0.564154 -0.034491 -0.116392 -0.816697 +VERTEX_SE3:QUAT 653 6.9155 -29.8393 -32.9911 -0.55604 -0.0471123 -0.187376 -0.808388 +VERTEX_SE3:QUAT 654 11.1106 -27.8612 -32.5684 -0.547412 -0.0627747 -0.241548 -0.798783 +VERTEX_SE3:QUAT 655 14.9427 -25.6657 -31.6837 -0.547428 -0.0592957 -0.323096 -0.769685 +VERTEX_SE3:QUAT 656 18.668 -22.6185 -30.3277 -0.531337 -0.0729339 -0.383955 -0.751626 +VERTEX_SE3:QUAT 657 21.66 -19.4038 -28.9487 -0.518751 -0.0824126 -0.438389 -0.729328 +VERTEX_SE3:QUAT 658 24.436 -15.7591 -27.4345 -0.496431 -0.0933783 -0.504904 -0.699935 +VERTEX_SE3:QUAT 659 26.4408 -11.8371 -25.7748 -0.477705 -0.0998189 -0.554297 -0.674232 +VERTEX_SE3:QUAT 660 28.1268 -7.80459 -23.8443 -0.453648 -0.12501 -0.595826 -0.650821 +VERTEX_SE3:QUAT 661 29.1641 -3.48002 -22.0895 -0.43965 -0.119252 -0.665335 -0.591452 +VERTEX_SE3:QUAT 662 29.3993 0.754538 -20.025 -0.411078 -0.116 -0.720808 -0.545889 +VERTEX_SE3:QUAT 663 28.8351 5.03148 -18.0077 -0.384889 -0.140634 -0.749916 -0.519335 +VERTEX_SE3:QUAT 664 27.952 9.06498 -16.0042 -0.363264 -0.130207 -0.80692 -0.447175 +VERTEX_SE3:QUAT 665 26.2261 12.9779 -13.8501 -0.328124 -0.129234 -0.843851 -0.404412 +VERTEX_SE3:QUAT 666 23.8497 16.5581 -11.7663 -0.291143 -0.13636 -0.870292 -0.373141 +VERTEX_SE3:QUAT 667 20.9299 19.9128 -9.83157 -0.252262 -0.146097 -0.896802 -0.332814 +VERTEX_SE3:QUAT 668 17.5409 23.0442 -8.36331 -0.216052 -0.155224 -0.919165 -0.290451 +VERTEX_SE3:QUAT 669 13.6418 25.7979 -7.20174 -0.18302 -0.164791 -0.934724 -0.256202 +VERTEX_SE3:QUAT 670 9.7763 28.2865 -5.98458 -0.138552 -0.175678 -0.951301 -0.212056 +VERTEX_SE3:QUAT 671 5.48078 30.1658 -5.35825 -0.0923059 -0.17836 -0.966073 -0.162391 +VERTEX_SE3:QUAT 672 0.820043 31.8423 -4.84642 -0.0575404 -0.185405 -0.974217 -0.11496 +VERTEX_SE3:QUAT 673 -3.91659 32.8089 -4.69464 -0.0225705 -0.19039 -0.980751 -0.0370107 +VERTEX_SE3:QUAT 674 -8.74969 32.9111 -4.79608 0.0227739 -0.191417 -0.981236 0.00417299 +VERTEX_SE3:QUAT 675 -13.7047 32.4526 -5.19962 0.057805 -0.192704 -0.976516 0.0770773 +VERTEX_SE3:QUAT 676 -18.1728 31.3674 -5.75622 0.0943343 -0.191412 -0.968759 0.126364 +VERTEX_SE3:QUAT 677 -22.717 29.8559 -6.67245 0.13059 -0.192251 -0.956889 0.174212 +VERTEX_SE3:QUAT 678 -27.041 27.6643 -7.66859 0.168015 -0.185444 -0.945292 0.209295 +VERTEX_SE3:QUAT 679 -30.9278 25.298 -9.0237 0.200199 -0.178387 -0.929896 0.251776 +VERTEX_SE3:QUAT 680 -34.6808 22.5687 -10.5062 0.240563 -0.176524 -0.909624 0.289057 +VERTEX_SE3:QUAT 681 -37.9653 19.3563 -12.2411 0.27431 -0.172296 -0.881007 0.344812 +VERTEX_SE3:QUAT 682 -40.7263 15.8545 -14.1011 0.310312 -0.168547 -0.85534 0.379067 +VERTEX_SE3:QUAT 683 -43.1613 12.2288 -16.0988 0.334808 -0.166728 -0.816646 0.439539 +VERTEX_SE3:QUAT 684 -44.7834 8.02192 -18.23 0.359083 -0.170667 -0.760954 0.512719 +VERTEX_SE3:QUAT 685 -45.7 3.65098 -20.0051 0.3995 -0.151578 -0.734363 0.527384 +VERTEX_SE3:QUAT 686 -46.0859 -0.722275 -22.223 0.43242 -0.131043 -0.702392 0.549988 +VERTEX_SE3:QUAT 687 -45.807 -4.91851 -24.4107 0.458423 -0.131166 -0.645305 0.596846 +VERTEX_SE3:QUAT 688 -44.8622 -9.12842 -26.4349 0.485767 -0.116948 -0.601852 0.622999 +VERTEX_SE3:QUAT 689 -43.288 -13.3296 -28.5733 0.511411 -0.130221 -0.519346 0.672146 +VERTEX_SE3:QUAT 690 -41.057 -17.2863 -30.0734 0.524352 -0.115797 -0.482374 0.69207 +VERTEX_SE3:QUAT 691 -38.4064 -21.0064 -31.8273 0.544708 -0.10268 -0.425097 0.715571 +VERTEX_SE3:QUAT 692 -35.2138 -24.3057 -33.3162 0.560251 -0.0898167 -0.373901 0.733655 +VERTEX_SE3:QUAT 693 -31.5558 -27.3409 -34.6526 0.565798 -0.0739729 -0.31416 0.758751 +VERTEX_SE3:QUAT 694 -27.5068 -29.8263 -35.6846 0.583678 -0.0548762 -0.265931 0.765238 +VERTEX_SE3:QUAT 695 -23.3732 -31.971 -36.6179 0.587156 -0.0628993 -0.18766 0.784904 +VERTEX_SE3:QUAT 696 -18.8665 -33.3527 -37.1266 0.589885 -0.0321112 -0.14063 0.794499 +VERTEX_SE3:QUAT 697 -14.1831 -34.3025 -37.6692 0.596095 -0.0121474 -0.0858249 0.798221 +VERTEX_SE3:QUAT 698 -9.29223 -34.917 -38.1779 0.597223 0.0075131 -0.011111 0.801963 +VERTEX_SE3:QUAT 699 -4.45496 -34.8002 -37.892 0.597067 0.037073 0.0334458 0.800636 +VERTEX_SE3:QUAT 700 0.448328 -34.143 -37.8928 0.592856 0.055279 0.0780872 0.799605 +VERTEX_SE3:QUAT 701 5.35671 -32.9608 -37.6851 0.594937 0.0728769 0.134551 0.789072 +VERTEX_SE3:QUAT 702 9.87964 -31.2163 -37.448 0.587691 0.0740755 0.199916 0.78049 +VERTEX_SE3:QUAT 703 14.3102 -29.1831 -36.7173 0.574286 0.10754 0.237395 0.776063 +VERTEX_SE3:QUAT 704 18.3997 -26.4777 -36.1707 0.56704 0.115938 0.31838 0.750772 +VERTEX_SE3:QUAT 705 21.8592 -23.2722 -35.1435 0.556993 0.124539 0.377097 0.729416 +VERTEX_SE3:QUAT 706 25.1249 -19.6066 -33.8707 0.545621 0.141983 0.423662 0.708977 +VERTEX_SE3:QUAT 707 27.831 -15.8538 -32.5363 0.523858 0.157212 0.476476 0.688351 +VERTEX_SE3:QUAT 708 30.0161 -11.6961 -31.166 0.514911 0.153793 0.549509 0.63973 +VERTEX_SE3:QUAT 709 31.518 -7.56753 -29.1909 0.495613 0.163953 0.601685 0.604535 +VERTEX_SE3:QUAT 710 32.3687 -3.12101 -27.3286 0.473868 0.165103 0.650021 0.570669 +VERTEX_SE3:QUAT 711 32.6233 1.3919 -25.249 0.451211 0.171406 0.696359 0.531143 +VERTEX_SE3:QUAT 712 32.2273 5.78858 -22.9788 0.408948 0.200339 0.721064 0.5222 +VERTEX_SE3:QUAT 713 31.6247 10.2563 -21.2479 0.374606 0.214018 0.761169 0.484241 +VERTEX_SE3:QUAT 714 30.0879 14.645 -19.4059 0.352471 0.223191 0.797564 0.435708 +VERTEX_SE3:QUAT 715 27.9785 18.6662 -17.6786 0.315479 0.22109 0.842869 0.375718 +VERTEX_SE3:QUAT 716 25.16 22.3035 -15.926 0.287798 0.233833 0.87349 0.315452 +VERTEX_SE3:QUAT 717 21.7874 25.6628 -14.2601 0.259807 0.227528 0.903324 0.254434 +VERTEX_SE3:QUAT 718 17.7668 28.2977 -12.54 0.217328 0.230431 0.92628 0.204145 +VERTEX_SE3:QUAT 719 13.3264 30.5239 -11.1799 0.187507 0.214204 0.95157 0.116067 +VERTEX_SE3:QUAT 720 8.56182 31.9322 -9.90287 0.158736 0.203456 0.964964 0.0474558 +VERTEX_SE3:QUAT 721 3.72077 32.5109 -8.59323 0.125531 0.1946 0.972556 -0.0225399 +VERTEX_SE3:QUAT 722 -1.09778 32.4465 -7.46956 0.0826953 0.182094 0.975854 -0.0878179 +VERTEX_SE3:QUAT 723 -5.96723 31.4279 -6.82817 0.0378201 0.1851 0.973051 -0.132207 +VERTEX_SE3:QUAT 724 -10.7987 29.9971 -6.54019 -0.000403471 0.180364 0.971226 -0.155527 +VERTEX_SE3:QUAT 725 -15.5464 28.0557 -6.49309 -0.03887 0.175386 0.954794 -0.236848 +VERTEX_SE3:QUAT 726 -20.0679 25.4073 -6.64725 -0.0889084 0.159387 0.94964 -0.254706 +VERTEX_SE3:QUAT 727 -24.2972 22.8045 -7.30019 -0.132431 0.141893 0.928869 -0.315485 +VERTEX_SE3:QUAT 728 -27.7538 19.5336 -8.2501 -0.166571 0.136873 0.90307 -0.371462 +VERTEX_SE3:QUAT 729 -31.0434 15.7312 -9.31117 -0.214347 0.11525 0.893016 -0.378545 +VERTEX_SE3:QUAT 730 -33.9066 11.8522 -11.17 -0.248834 0.103765 0.873063 -0.406295 +VERTEX_SE3:QUAT 731 -36.5046 7.87434 -13.0684 -0.292729 0.0922948 0.847694 -0.432673 +VERTEX_SE3:QUAT 732 -38.5522 3.94832 -15.4238 -0.32694 0.0872385 0.805595 -0.486329 +VERTEX_SE3:QUAT 733 -39.8943 -0.382291 -17.8872 -0.366941 0.0740123 0.76674 -0.521522 +VERTEX_SE3:QUAT 734 -40.5908 -4.5588 -20.6175 -0.392658 0.0669494 0.712566 -0.57757 +VERTEX_SE3:QUAT 735 -40.5284 -8.98863 -23.1186 -0.417954 0.0620513 0.654838 -0.626619 +VERTEX_SE3:QUAT 736 -39.5574 -13.3673 -25.2758 -0.454602 0.0483567 0.609785 -0.647427 +VERTEX_SE3:QUAT 737 -37.8802 -17.5272 -27.8442 -0.481398 0.0277381 0.570057 -0.665223 +VERTEX_SE3:QUAT 738 -35.8496 -21.4296 -30.5037 -0.510152 0.00826899 0.513246 -0.690112 +VERTEX_SE3:QUAT 739 -33.1722 -24.7463 -33.1813 -0.536571 -0.00971162 0.469802 -0.700916 +VERTEX_SE3:QUAT 740 -30.2846 -27.7825 -35.9624 -0.558254 -0.0440222 0.437293 -0.703697 +VERTEX_SE3:QUAT 741 -27.0195 -30.5447 -38.7483 -0.581038 -0.0504435 0.372154 -0.722047 +VERTEX_SE3:QUAT 742 -23.3409 -32.8713 -41.3615 -0.605781 -0.0530622 0.309156 -0.731188 +VERTEX_SE3:QUAT 743 -19.1788 -34.6452 -43.5959 -0.622706 -0.0710681 0.247626 -0.738829 +VERTEX_SE3:QUAT 744 -14.6468 -35.7505 -45.7538 -0.639428 -0.0811734 0.190213 -0.740515 +VERTEX_SE3:QUAT 745 -9.92956 -36.4891 -47.7761 -0.654451 -0.0754372 0.100258 -0.745622 +VERTEX_SE3:QUAT 746 -5.04159 -36.4898 -48.7281 -0.665554 -0.079848 0.0345467 -0.741261 +VERTEX_SE3:QUAT 747 -0.116582 -35.9982 -49.6617 -0.672808 -0.0959562 -0.0258925 -0.733111 +VERTEX_SE3:QUAT 748 4.96793 -34.8161 -50.154 -0.675516 -0.0750391 -0.121931 -0.723312 +VERTEX_SE3:QUAT 749 9.91012 -32.983 -49.8628 -0.676191 -0.0732493 -0.183651 -0.709699 +VERTEX_SE3:QUAT 750 14.5709 -30.9321 -48.7645 -0.666426 -0.0771056 -0.243348 -0.700509 +VERTEX_SE3:QUAT 751 19.0837 -28.5618 -47.4568 -0.653769 -0.0978009 -0.292713 -0.690898 +VERTEX_SE3:QUAT 752 23.0189 -25.7688 -46.1515 -0.644574 -0.11849 -0.343802 -0.672521 +VERTEX_SE3:QUAT 753 26.7055 -22.3699 -44.9269 -0.633669 -0.131635 -0.399502 -0.649256 +VERTEX_SE3:QUAT 754 29.7575 -18.8284 -43.2916 -0.620021 -0.161186 -0.435695 -0.632268 +VERTEX_SE3:QUAT 755 32.4619 -14.9534 -41.5598 -0.606388 -0.168462 -0.489324 -0.603719 +VERTEX_SE3:QUAT 756 34.6569 -10.4941 -39.5149 -0.587171 -0.176969 -0.541572 -0.574988 +VERTEX_SE3:QUAT 757 36.1948 -6.09059 -37.366 -0.556633 -0.199399 -0.580499 -0.55984 +VERTEX_SE3:QUAT 758 37.1013 -1.50745 -35.3065 -0.531902 -0.206304 -0.62928 -0.527756 +VERTEX_SE3:QUAT 759 37.4359 3.07571 -32.9016 -0.499597 -0.244635 -0.646147 -0.522543 +VERTEX_SE3:QUAT 760 37.4048 7.71281 -31.0367 -0.471847 -0.253365 -0.69654 -0.477493 +VERTEX_SE3:QUAT 761 36.8026 12.5244 -28.8182 -0.435836 -0.264123 -0.742011 -0.435552 +VERTEX_SE3:QUAT 762 35.0623 16.8988 -26.8481 -0.426559 -0.24943 -0.790325 -0.362241 +VERTEX_SE3:QUAT 763 32.7916 20.7183 -24.4119 -0.39036 -0.269578 -0.814109 -0.334924 +VERTEX_SE3:QUAT 764 30.0522 24.5681 -21.9532 -0.367458 -0.261807 -0.852539 -0.263836 +VERTEX_SE3:QUAT 765 26.7797 27.7529 -19.6497 -0.324696 -0.266795 -0.878298 -0.228003 +VERTEX_SE3:QUAT 766 22.95 30.6163 -17.4856 -0.289536 -0.269045 -0.902228 -0.172532 +VERTEX_SE3:QUAT 767 18.8101 32.6818 -15.2607 -0.249355 -0.264291 -0.923357 -0.124036 +VERTEX_SE3:QUAT 768 14.2668 34.2499 -13.3708 -0.211544 -0.25607 -0.940641 -0.0698018 +VERTEX_SE3:QUAT 769 9.35132 35.4032 -11.4626 -0.165961 -0.248369 -0.953998 -0.0256485 +VERTEX_SE3:QUAT 770 4.39999 36.0689 -9.94884 -0.120265 -0.23557 -0.964273 0.0148423 +VERTEX_SE3:QUAT 771 -0.639823 36.0325 -9.03037 -0.0806987 -0.227381 -0.968754 0.0574598 +VERTEX_SE3:QUAT 772 -5.74633 35.2901 -8.2852 -0.0404063 -0.215401 -0.968899 0.114915 +VERTEX_SE3:QUAT 773 -10.7536 34.0003 -7.50788 0.0051934 -0.209419 -0.964256 0.162258 +VERTEX_SE3:QUAT 774 -15.5054 32.217 -7.20565 0.0439311 -0.20216 -0.958232 0.197466 +VERTEX_SE3:QUAT 775 -20.1926 29.9112 -7.32233 0.0966099 -0.198595 -0.949663 0.222187 +VERTEX_SE3:QUAT 776 -24.6366 27.1717 -8.13272 0.132352 -0.198567 -0.932018 0.272758 +VERTEX_SE3:QUAT 777 -28.741 24.0362 -9.14466 0.182325 -0.175927 -0.92675 0.277384 +VERTEX_SE3:QUAT 778 -32.7495 20.9072 -10.5115 0.218873 -0.170247 -0.892663 0.355335 +VERTEX_SE3:QUAT 779 -36.145 16.9663 -12.2754 0.259861 -0.161186 -0.863607 0.400841 +VERTEX_SE3:QUAT 780 -38.7152 12.731 -14.0094 0.298765 -0.150525 -0.8432 0.420827 +VERTEX_SE3:QUAT 781 -41.0013 8.34563 -16.0029 0.337675 -0.123519 -0.824999 0.436 +VERTEX_SE3:QUAT 782 -42.8821 4.04071 -18.5073 0.373295 -0.125306 -0.786367 0.476001 +VERTEX_SE3:QUAT 783 -43.9116 -0.552674 -21.1035 0.406018 -0.118086 -0.728605 0.538831 +VERTEX_SE3:QUAT 784 -44.1877 -5.22471 -23.6928 0.440447 -0.103559 -0.674523 0.583353 +VERTEX_SE3:QUAT 785 -43.455 -9.78767 -26.1158 0.465284 -0.0799015 -0.63909 0.6072 +VERTEX_SE3:QUAT 786 -42.1989 -14.0816 -28.805 0.506751 -0.0514688 -0.611078 0.605919 +VERTEX_SE3:QUAT 787 -40.505 -18.2935 -31.7814 0.531053 -0.0298593 -0.587465 0.609898 +VERTEX_SE3:QUAT 788 -38.6211 -22.1824 -34.9577 0.561718 -0.018976 -0.534358 0.631327 +VERTEX_SE3:QUAT 789 -36.0872 -25.8201 -38.0102 0.583449 -0.00930668 -0.47927 0.655592 +VERTEX_SE3:QUAT 790 -33.0476 -28.986 -40.8568 0.602799 0.00874738 -0.425189 0.675108 +VERTEX_SE3:QUAT 791 -29.499 -31.8197 -43.537 0.62241 0.00850989 -0.339349 0.705248 +VERTEX_SE3:QUAT 792 -25.1196 -34.1165 -45.8784 0.64555 0.00800007 -0.273566 0.712996 +VERTEX_SE3:QUAT 793 -20.4233 -35.8757 -47.7424 0.662899 0.0177058 -0.21491 0.716983 +VERTEX_SE3:QUAT 794 -15.3481 -36.9669 -49.3018 0.679572 0.0430844 -0.165109 0.713487 +VERTEX_SE3:QUAT 795 -10.2918 -37.4415 -50.7553 0.688599 0.0715382 -0.106208 0.713746 +VERTEX_SE3:QUAT 796 -5.19156 -37.4873 -51.985 0.699795 0.0854531 -0.0422264 0.707956 +VERTEX_SE3:QUAT 797 0.0962433 -36.7252 -52.8984 0.697382 0.120769 0.0136652 0.706319 +VERTEX_SE3:QUAT 798 5.07203 -35.4745 -53.6814 0.695223 0.128566 0.0709753 0.703633 +VERTEX_SE3:QUAT 799 10.2863 -33.7098 -53.8157 0.690187 0.142383 0.126185 0.698173 +VERTEX_SE3:QUAT 800 15.0591 -31.6492 -53.9176 0.686496 0.138152 0.202399 0.684596 +VERTEX_SE3:QUAT 801 19.6657 -28.9458 -53.3279 0.681744 0.146124 0.2631 0.666821 +VERTEX_SE3:QUAT 802 23.8315 -25.7827 -52.4366 0.672602 0.13714 0.334147 0.645868 +VERTEX_SE3:QUAT 803 27.2906 -22.4363 -50.7091 0.658384 0.164621 0.377444 0.630052 +VERTEX_SE3:QUAT 804 30.5381 -18.609 -49.0939 0.637339 0.187326 0.429291 0.611896 +VERTEX_SE3:QUAT 805 33.3679 -14.3355 -47.4229 0.626839 0.190308 0.478869 0.584415 +VERTEX_SE3:QUAT 806 35.556 -9.80582 -45.149 0.607056 0.206961 0.521387 0.562855 +VERTEX_SE3:QUAT 807 37.4349 -5.19647 -42.979 0.584884 0.196367 0.593851 0.516423 +VERTEX_SE3:QUAT 808 38.3005 -0.570004 -40.3955 0.549711 0.234093 0.611676 0.518527 +VERTEX_SE3:QUAT 809 38.6807 4.31606 -37.8892 0.526865 0.247149 0.652913 0.484804 +VERTEX_SE3:QUAT 810 38.4606 8.9204 -35.4652 0.497681 0.238883 0.709427 0.438136 +VERTEX_SE3:QUAT 811 37.499 13.6749 -32.9954 0.475063 0.257498 0.735372 0.408947 +VERTEX_SE3:QUAT 812 35.9684 18.2067 -30.4506 0.442293 0.263909 0.768927 0.378789 +VERTEX_SE3:QUAT 813 34.1634 22.447 -27.8712 0.412508 0.273643 0.792939 0.355252 +VERTEX_SE3:QUAT 814 31.7827 26.5185 -25.4117 0.389535 0.254086 0.838847 0.28291 +VERTEX_SE3:QUAT 815 28.6996 30.1025 -22.7147 0.345934 0.269268 0.860352 0.260036 +VERTEX_SE3:QUAT 816 25.2114 33.3522 -20.2299 0.310074 0.272193 0.884453 0.217961 +VERTEX_SE3:QUAT 817 21.0626 36.0624 -17.966 0.258346 0.285438 0.897837 0.213707 +VERTEX_SE3:QUAT 818 16.5501 38.6151 -16.3284 0.217628 0.283854 0.918054 0.171003 +VERTEX_SE3:QUAT 819 11.7013 40.7053 -14.8332 0.177657 0.27861 0.938573 0.0994747 +VERTEX_SE3:QUAT 820 6.75285 42.0914 -13.4051 0.131595 0.275318 0.951363 0.042327 +VERTEX_SE3:QUAT 821 1.4452 42.7126 -12.4386 0.0754893 0.277348 0.957431 0.0265441 +VERTEX_SE3:QUAT 822 -3.9057 42.9032 -11.7986 0.0339764 0.274168 0.960814 -0.0226724 +VERTEX_SE3:QUAT 823 -9.3377 42.4185 -11.5216 -0.017323 0.272792 0.960895 -0.0443426 +VERTEX_SE3:QUAT 824 -14.703 41.4912 -11.8438 -0.0584924 0.276269 0.956685 -0.0707655 +VERTEX_SE3:QUAT 825 -19.9307 40.3371 -12.3916 -0.102455 0.271517 0.950519 -0.110886 +VERTEX_SE3:QUAT 826 -25.0777 38.6968 -13.2723 -0.139508 0.273088 0.939024 -0.155543 +VERTEX_SE3:QUAT 827 -29.9805 36.769 -14.3795 -0.175832 0.280457 0.920032 -0.209686 +VERTEX_SE3:QUAT 828 -34.5006 34.1273 -15.6143 -0.222956 0.272318 0.908074 -0.227014 +VERTEX_SE3:QUAT 829 -38.6063 31.1062 -17.3463 -0.256075 0.264833 0.889054 -0.271794 +VERTEX_SE3:QUAT 830 -42.1548 27.501 -19.0826 -0.301457 0.242781 0.880127 -0.274878 +VERTEX_SE3:QUAT 831 -45.6866 23.9542 -21.4311 -0.345835 0.232555 0.860481 -0.293068 +VERTEX_SE3:QUAT 832 -48.5077 20.1994 -24.1896 -0.375246 0.231507 0.828798 -0.344511 +VERTEX_SE3:QUAT 833 -50.8717 15.8613 -26.8262 -0.422752 0.217319 0.808624 -0.34667 +VERTEX_SE3:QUAT 834 -52.827 11.6247 -29.7683 -0.458357 0.218189 0.770436 -0.385657 +VERTEX_SE3:QUAT 835 -54.2425 7.13999 -32.8345 -0.493421 0.209795 0.741136 -0.404028 +VERTEX_SE3:QUAT 836 -54.8803 2.74765 -36.0766 -0.540373 0.179178 0.712292 -0.410527 +VERTEX_SE3:QUAT 837 -54.9291 -1.62493 -39.5441 -0.573483 0.17062 0.669881 -0.439619 +VERTEX_SE3:QUAT 838 -54.3248 -5.77432 -42.8513 -0.599177 0.161085 0.63448 -0.460949 +VERTEX_SE3:QUAT 839 -53.1357 -9.9449 -46.133 -0.621621 0.172391 0.581802 -0.495354 +VERTEX_SE3:QUAT 840 -51.3478 -14.1873 -49.0638 -0.635518 0.194535 0.512331 -0.543866 +VERTEX_SE3:QUAT 841 -48.8918 -18.6161 -51.4948 -0.664427 0.179678 0.459644 -0.561231 +VERTEX_SE3:QUAT 842 -45.8912 -22.654 -53.4783 -0.679388 0.177449 0.401712 -0.587853 +VERTEX_SE3:QUAT 843 -42.4146 -26.3707 -55.3942 -0.691319 0.17915 0.335195 -0.614515 +VERTEX_SE3:QUAT 844 -38.3966 -29.8306 -56.4966 -0.709466 0.170137 0.27785 -0.624909 +VERTEX_SE3:QUAT 845 -33.8085 -32.778 -57.452 -0.721258 0.154899 0.216495 -0.639471 +VERTEX_SE3:QUAT 846 -28.9042 -35.2213 -57.9798 -0.737657 0.112206 0.183455 -0.640012 +VERTEX_SE3:QUAT 847 -23.9073 -37.155 -58.5521 -0.73925 0.111027 0.120476 -0.653199 +VERTEX_SE3:QUAT 848 -18.731 -38.5616 -58.7384 -0.742053 0.108799 0.0361995 -0.660462 +VERTEX_SE3:QUAT 849 -13.5471 -39.3952 -58.1341 -0.734823 0.105781 -0.0328521 -0.669153 +VERTEX_SE3:QUAT 850 -8.23945 -39.6734 -56.8858 -0.740558 0.0815959 -0.0886579 -0.661102 +VERTEX_SE3:QUAT 851 -2.92249 -39.2902 -55.232 -0.731457 0.0537579 -0.136045 -0.666012 +VERTEX_SE3:QUAT 852 2.3103 -38.5423 -53.608 -0.728075 0.0296827 -0.186352 -0.659014 +VERTEX_SE3:QUAT 853 7.28067 -37.1925 -51.7423 -0.717554 0.0362491 -0.256826 -0.646407 +VERTEX_SE3:QUAT 854 11.8713 -35.4009 -49.2452 -0.698656 0.00684718 -0.3164 -0.641657 +VERTEX_SE3:QUAT 855 15.9987 -32.9207 -46.514 -0.684824 -0.0095705 -0.371923 -0.626576 +VERTEX_SE3:QUAT 856 19.9844 -30.0228 -43.7401 -0.663896 -0.0469912 -0.406736 -0.62578 +VERTEX_SE3:QUAT 857 23.2379 -26.7734 -41.0643 -0.642131 -0.0634369 -0.460607 -0.609495 +VERTEX_SE3:QUAT 858 26.0312 -22.8574 -38.1897 -0.618325 -0.0740202 -0.508351 -0.59479 +VERTEX_SE3:QUAT 859 28.4284 -18.7561 -35.3037 -0.588448 -0.108566 -0.54584 -0.586516 +VERTEX_SE3:QUAT 860 30.4167 -14.1618 -32.4923 -0.560402 -0.128079 -0.587932 -0.569105 +VERTEX_SE3:QUAT 861 31.7895 -9.59218 -29.8544 -0.531971 -0.166164 -0.610799 -0.562425 +VERTEX_SE3:QUAT 862 32.4719 -4.67955 -27.5021 -0.506994 -0.183527 -0.6548 -0.529634 +VERTEX_SE3:QUAT 863 32.5447 0.313143 -24.9252 -0.476151 -0.182777 -0.712037 -0.482573 +VERTEX_SE3:QUAT 864 31.7815 5.25179 -22.2025 -0.436869 -0.19599 -0.756457 -0.445541 +VERTEX_SE3:QUAT 865 30.1702 9.86043 -19.5733 -0.402594 -0.216565 -0.776149 -0.434293 +VERTEX_SE3:QUAT 866 28.201 14.4473 -17.2627 -0.371824 -0.218355 -0.811389 -0.394609 +VERTEX_SE3:QUAT 867 25.4957 19.0204 -14.8408 -0.322423 -0.242407 -0.833319 -0.37797 +VERTEX_SE3:QUAT 868 22.3682 23.2251 -12.9085 -0.277272 -0.254361 -0.861317 -0.341399 +VERTEX_SE3:QUAT 869 18.6693 27.2079 -11.4571 -0.22337 -0.272925 -0.875113 -0.331352 +VERTEX_SE3:QUAT 870 14.7867 31.1672 -10.496 -0.175723 -0.284005 -0.898301 -0.285512 +VERTEX_SE3:QUAT 871 10.1619 34.457 -9.91532 -0.132389 -0.286261 -0.923751 -0.217284 +VERTEX_SE3:QUAT 872 5.15547 36.9633 -9.34073 -0.0828036 -0.297282 -0.934577 -0.177009 +VERTEX_SE3:QUAT 873 -0.131101 38.9469 -9.29647 -0.0462339 -0.298295 -0.943502 -0.136696 +VERTEX_SE3:QUAT 874 -5.45693 40.155 -9.47436 0.00828454 -0.299801 -0.948868 -0.0984951 +VERTEX_SE3:QUAT 875 -10.8686 40.9153 -9.95006 0.0487279 -0.303044 -0.948588 -0.0772701 +VERTEX_SE3:QUAT 876 -16.3731 41.4346 -10.9601 0.0993082 -0.308882 -0.944436 -0.0526378 +VERTEX_SE3:QUAT 877 -21.9874 41.3577 -12.4434 0.13545 -0.322959 -0.936666 -0.00287941 +VERTEX_SE3:QUAT 878 -27.297 40.6974 -13.9608 0.170839 -0.323052 -0.929228 0.0546584 +VERTEX_SE3:QUAT 879 -32.3206 39.2796 -15.6015 0.229805 -0.314784 -0.91899 0.0596606 +VERTEX_SE3:QUAT 880 -37.2213 37.5513 -17.9409 0.256095 -0.318762 -0.901378 0.142565 +VERTEX_SE3:QUAT 881 -41.7117 34.7729 -20.3695 0.297929 -0.315598 -0.880252 0.191814 +VERTEX_SE3:QUAT 882 -45.8805 31.5909 -22.6853 0.325546 -0.316676 -0.85513 0.249978 +VERTEX_SE3:QUAT 883 -49.5768 27.7305 -25.1071 0.365103 -0.31403 -0.819994 0.309345 +VERTEX_SE3:QUAT 884 -52.6539 23.4248 -27.3475 0.400032 -0.309448 -0.789886 0.346838 +VERTEX_SE3:QUAT 885 -54.7106 18.9474 -29.872 0.431636 -0.303524 -0.751865 0.395301 +VERTEX_SE3:QUAT 886 -56.1108 14.003 -32.1403 0.464804 -0.297433 -0.708014 0.440688 +VERTEX_SE3:QUAT 887 -56.7054 8.76779 -34.4683 0.482982 -0.301461 -0.660618 0.489319 +VERTEX_SE3:QUAT 888 -56.7698 3.42566 -36.3539 0.510771 -0.287342 -0.620992 0.520497 +VERTEX_SE3:QUAT 889 -55.9948 -1.8243 -38.2517 0.526043 -0.285797 -0.559931 0.57278 +VERTEX_SE3:QUAT 890 -54.4155 -7.21319 -39.723 0.546746 -0.275097 -0.502662 0.610509 +VERTEX_SE3:QUAT 891 -52.0522 -12.3975 -41.1406 0.565991 -0.252447 -0.450956 0.642311 +VERTEX_SE3:QUAT 892 -49.0651 -17.1481 -42.3774 0.589248 -0.231746 -0.395328 0.66543 +VERTEX_SE3:QUAT 893 -45.4917 -21.4018 -43.2469 0.616389 -0.188549 -0.371928 0.66797 +VERTEX_SE3:QUAT 894 -41.5135 -25.3258 -44.3209 0.626148 -0.181767 -0.303187 0.694965 +VERTEX_SE3:QUAT 895 -37.0725 -28.8063 -45.0507 0.635912 -0.15881 -0.238485 0.716603 +VERTEX_SE3:QUAT 896 -32.0726 -31.4919 -45.568 0.64315 -0.129575 -0.190719 0.730202 +VERTEX_SE3:QUAT 897 -26.8384 -33.7583 -45.9658 0.652168 -0.0897931 -0.149801 0.737682 +VERTEX_SE3:QUAT 898 -21.2578 -35.5683 -46.2624 0.661053 -0.0517735 -0.103443 0.741369 +VERTEX_SE3:QUAT 899 -15.6538 -36.5381 -46.5258 0.65636 -0.0469498 -0.0276733 0.752476 +VERTEX_SE3:QUAT 900 -9.95278 -36.9636 -46.3469 0.657339 -0.042511 0.0445935 0.751073 +VERTEX_SE3:QUAT 901 -4.19529 -36.5767 -45.5469 0.652151 -0.0225353 0.100459 0.751066 +VERTEX_SE3:QUAT 902 1.21293 -35.5243 -44.5771 0.646102 -0.0016755 0.157367 0.74685 +VERTEX_SE3:QUAT 903 6.48899 -33.7255 -43.4539 0.635694 0.0192758 0.221711 0.739166 +VERTEX_SE3:QUAT 904 11.637 -31.4468 -42.1092 0.620347 0.0187888 0.296934 0.725704 +VERTEX_SE3:QUAT 905 16.1702 -28.5632 -40.1309 0.603891 0.0362147 0.36144 0.709483 +VERTEX_SE3:QUAT 906 20.1788 -25.2227 -38.0344 0.585461 0.0743403 0.402527 0.699772 +VERTEX_SE3:QUAT 907 23.6947 -21.2075 -36.0783 0.568611 0.121473 0.419833 0.696897 +VERTEX_SE3:QUAT 908 26.9643 -16.7912 -34.3496 0.540687 0.132228 0.481913 0.676708 +VERTEX_SE3:QUAT 909 29.5291 -11.9596 -32.5302 0.511729 0.162592 0.525401 0.660039 +VERTEX_SE3:QUAT 910 31.4077 -6.75173 -30.867 0.488122 0.170672 0.586261 0.623624 +VERTEX_SE3:QUAT 911 32.508 -1.33095 -28.7921 0.447112 0.20901 0.609361 0.620552 +VERTEX_SE3:QUAT 912 33.1927 4.23708 -27.1574 0.422863 0.232317 0.650844 0.586189 +VERTEX_SE3:QUAT 913 33.001 9.63934 -25.6536 0.386609 0.280622 0.659326 0.580581 +VERTEX_SE3:QUAT 914 32.566 15.1901 -24.7561 0.350677 0.310741 0.691977 0.549212 +VERTEX_SE3:QUAT 915 31.4647 20.7779 -24.0592 0.323096 0.325448 0.723061 0.5166 +VERTEX_SE3:QUAT 916 29.5556 26.1452 -23.4439 0.286269 0.346583 0.759479 0.470235 +VERTEX_SE3:QUAT 917 26.949 31.3783 -22.8115 0.248724 0.369153 0.777342 0.444524 +VERTEX_SE3:QUAT 918 23.777 36.2926 -22.6269 0.225069 0.373168 0.821778 0.367112 +VERTEX_SE3:QUAT 919 19.9598 40.4429 -22.2453 0.193068 0.389805 0.840954 0.321827 +VERTEX_SE3:QUAT 920 15.578 44.1716 -22.0434 0.14288 0.405621 0.848763 0.307665 +VERTEX_SE3:QUAT 921 10.9385 47.7145 -22.2297 0.0809332 0.423654 0.852804 0.294438 +VERTEX_SE3:QUAT 922 6.1236 50.6124 -23.0939 0.0504362 0.435183 0.864409 0.246714 +VERTEX_SE3:QUAT 923 1.04412 53.0695 -23.9754 0.0294646 0.433977 0.881918 0.181702 +VERTEX_SE3:QUAT 924 -4.30532 54.6569 -24.6889 -0.018308 0.455428 0.875916 0.158181 +VERTEX_SE3:QUAT 925 -9.77429 55.7973 -25.8827 -0.0428834 0.462666 0.880046 0.0980805 +VERTEX_SE3:QUAT 926 -15.579 56.29 -26.7904 -0.0981587 0.463261 0.879401 0.0490838 +VERTEX_SE3:QUAT 927 -21.2865 55.8136 -28.2052 -0.130596 0.462723 0.876786 -0.00890498 +VERTEX_SE3:QUAT 928 -26.7856 54.6255 -29.5312 -0.174392 0.463042 0.868156 -0.038528 +VERTEX_SE3:QUAT 929 -32.0499 53.1098 -31.1541 -0.221068 0.46438 0.853891 -0.0796954 +VERTEX_SE3:QUAT 930 -37.0947 50.8666 -33.0788 -0.247097 0.473133 0.833235 -0.144245 +VERTEX_SE3:QUAT 931 -41.8831 47.8825 -34.8429 -0.296463 0.459094 0.818315 -0.178052 +VERTEX_SE3:QUAT 932 -46.0897 44.3405 -36.8452 -0.342531 0.458556 0.790805 -0.216854 +VERTEX_SE3:QUAT 933 -49.7435 40.1828 -38.6423 -0.369929 0.450454 0.765756 -0.271774 +VERTEX_SE3:QUAT 934 -52.8801 35.6031 -40.5019 -0.414449 0.437036 0.739256 -0.301217 +VERTEX_SE3:QUAT 935 -55.3434 30.7444 -42.3551 -0.461415 0.433198 0.698982 -0.332955 +VERTEX_SE3:QUAT 936 -57.0605 25.5581 -44.1654 -0.478083 0.427957 0.664478 -0.383091 +VERTEX_SE3:QUAT 937 -58.3411 20.0473 -45.8681 -0.500833 0.424997 0.610367 -0.442715 +VERTEX_SE3:QUAT 938 -58.6164 14.3746 -47.0356 -0.51568 0.415408 0.564471 -0.492831 +VERTEX_SE3:QUAT 939 -58.1548 8.56645 -48.1046 -0.543296 0.402038 0.502501 -0.539154 +VERTEX_SE3:QUAT 940 -56.6437 3.13513 -48.7134 -0.565026 0.377438 0.472527 -0.561252 +VERTEX_SE3:QUAT 941 -54.5929 -2.63664 -49.3764 -0.580708 0.361718 0.426031 -0.591976 +VERTEX_SE3:QUAT 942 -52.0098 -7.99068 -49.6155 -0.604869 0.326162 0.381623 -0.618155 +VERTEX_SE3:QUAT 943 -48.8203 -12.7032 -50.0439 -0.606681 0.318734 0.309704 -0.659113 +VERTEX_SE3:QUAT 944 -45.0044 -17.3041 -49.8675 -0.619431 0.290612 0.2538 -0.683693 +VERTEX_SE3:QUAT 945 -40.5837 -21.2384 -49.1903 -0.621384 0.27038 0.189879 -0.710439 +VERTEX_SE3:QUAT 946 -35.825 -24.4875 -48.3032 -0.631503 0.229979 0.137074 -0.727684 +VERTEX_SE3:QUAT 947 -30.6133 -26.8548 -47.4306 -0.627697 0.221964 0.0654202 -0.743269 +VERTEX_SE3:QUAT 948 -25.2428 -28.8304 -45.8336 -0.61657 0.202535 0.0055525 -0.760783 +VERTEX_SE3:QUAT 949 -19.8436 -30.0309 -43.9397 -0.604709 0.179096 -0.0558644 -0.774035 +VERTEX_SE3:QUAT 950 -14.4158 -30.5656 -41.9374 -0.595028 0.149744 -0.122755 -0.780032 +VERTEX_SE3:QUAT 951 -8.84812 -30.1436 -39.871 -0.586125 0.107289 -0.16748 -0.785428 +VERTEX_SE3:QUAT 952 -3.44092 -28.953 -37.7063 -0.570463 0.088104 -0.233805 -0.782397 +VERTEX_SE3:QUAT 953 1.53716 -27.2333 -35.3205 -0.545426 0.0732087 -0.304258 -0.777546 +VERTEX_SE3:QUAT 954 6.16345 -24.6233 -32.7952 -0.524506 0.0512195 -0.369324 -0.765421 +VERTEX_SE3:QUAT 955 10.3866 -21.2056 -30.305 -0.503616 0.0160008 -0.398959 -0.766125 +VERTEX_SE3:QUAT 956 14.1135 -17.4037 -28.0003 -0.478216 -0.0372138 -0.429019 -0.76542 +VERTEX_SE3:QUAT 957 17.5425 -12.9189 -26.0465 -0.453952 -0.047022 -0.496833 -0.738155 +VERTEX_SE3:QUAT 958 20.314 -8.07001 -23.876 -0.421385 -0.0774017 -0.539753 -0.724645 +VERTEX_SE3:QUAT 959 22.4337 -3.04668 -21.9517 -0.389156 -0.12572 -0.571566 -0.711382 +VERTEX_SE3:QUAT 960 24.0859 2.43 -20.509 -0.360017 -0.164105 -0.594877 -0.699699 +VERTEX_SE3:QUAT 961 25.2544 8.22252 -19.6766 -0.318653 -0.193258 -0.627139 -0.683965 +VERTEX_SE3:QUAT 962 25.7731 14.0088 -19.0773 -0.271873 -0.244136 -0.63899 -0.676886 +VERTEX_SE3:QUAT 963 25.8583 19.8308 -18.9645 -0.234342 -0.278661 -0.657094 -0.660045 +VERTEX_SE3:QUAT 964 25.4397 25.7964 -19.67 -0.197245 -0.31055 -0.690715 -0.622548 +VERTEX_SE3:QUAT 965 24.3554 31.5046 -20.5459 -0.165036 -0.340486 -0.713758 -0.589391 +VERTEX_SE3:QUAT 966 22.6623 37.139 -21.6963 -0.128314 -0.366556 -0.746967 -0.539641 +VERTEX_SE3:QUAT 967 19.9792 42.2962 -22.9744 -0.0982802 -0.389653 -0.766989 -0.500239 +VERTEX_SE3:QUAT 968 16.8503 46.9494 -24.4415 -0.0713431 -0.411331 -0.79695 -0.436563 +VERTEX_SE3:QUAT 969 13.1364 51.1313 -25.9807 -0.0335051 -0.427499 -0.813091 -0.393707 +VERTEX_SE3:QUAT 970 8.88695 54.8352 -27.8235 -0.0156288 -0.446655 -0.839508 -0.309001 +VERTEX_SE3:QUAT 971 3.90239 57.5777 -29.4348 0.0233043 -0.463364 -0.841663 -0.276321 +VERTEX_SE3:QUAT 972 -1.18152 59.881 -31.2113 0.0498343 -0.482253 -0.845575 -0.223499 +VERTEX_SE3:QUAT 973 -6.64489 61.6096 -33.1077 0.0917549 -0.506634 -0.840472 -0.168849 +VERTEX_SE3:QUAT 974 -12.179 62.2318 -35.1631 0.129039 -0.519777 -0.836 -0.119522 +VERTEX_SE3:QUAT 975 -17.6466 62.369 -37.2035 0.185116 -0.526485 -0.823834 -0.0992105 +VERTEX_SE3:QUAT 976 -22.8524 61.781 -39.6853 0.254724 -0.524632 -0.806758 -0.0949684 +VERTEX_SE3:QUAT 977 -27.77 60.6257 -42.7249 0.299805 -0.531801 -0.79028 -0.0525568 +VERTEX_SE3:QUAT 978 -32.4727 58.901 -45.8809 0.319436 -0.543796 -0.775973 0.0105942 +VERTEX_SE3:QUAT 979 -36.9474 56.4126 -48.8709 0.349804 -0.548889 -0.756374 0.0652413 +VERTEX_SE3:QUAT 980 -41.1207 53.2599 -51.6722 0.396548 -0.54449 -0.732346 0.0997496 +VERTEX_SE3:QUAT 981 -44.613 49.5694 -54.2571 0.437163 -0.535314 -0.707917 0.145538 +VERTEX_SE3:QUAT 982 -47.6762 45.4371 -56.995 0.476936 -0.529724 -0.680538 0.169682 +VERTEX_SE3:QUAT 983 -50.4974 40.8122 -59.6302 0.511434 -0.532972 -0.639623 0.212739 +VERTEX_SE3:QUAT 984 -52.3009 35.677 -62.0516 0.526718 -0.53594 -0.599549 0.275461 +VERTEX_SE3:QUAT 985 -53.7064 30.0478 -64.0342 0.54877 -0.532548 -0.561078 0.316916 +VERTEX_SE3:QUAT 986 -54.3902 24.3914 -65.5376 0.568166 -0.521882 -0.53178 0.349336 +VERTEX_SE3:QUAT 987 -54.6138 18.5936 -66.7669 0.597962 -0.501676 -0.493752 0.383369 +VERTEX_SE3:QUAT 988 -54.1791 12.8882 -67.8058 0.620569 -0.474865 -0.45506 0.426988 +VERTEX_SE3:QUAT 989 -53.1887 7.10602 -68.691 0.627789 -0.463456 -0.410018 0.472202 +VERTEX_SE3:QUAT 990 -51.4091 1.38097 -68.9541 0.639579 -0.459023 -0.353709 0.5051 +VERTEX_SE3:QUAT 991 -48.9487 -4.10607 -68.6953 0.63308 -0.45928 -0.292485 0.550203 +VERTEX_SE3:QUAT 992 -46.2945 -9.2874 -67.8245 0.642731 -0.434873 -0.237173 0.584407 +VERTEX_SE3:QUAT 993 -42.8922 -14.118 -66.435 0.628695 -0.432774 -0.161858 0.625501 +VERTEX_SE3:QUAT 994 -39.2094 -18.4268 -64.34 0.638781 -0.398383 -0.130375 0.645176 +VERTEX_SE3:QUAT 995 -35.1676 -22.312 -62.0897 0.62401 -0.395189 -0.0534013 0.672001 +VERTEX_SE3:QUAT 996 -30.9314 -25.4339 -59.2721 0.613144 -0.381112 0.00790993 0.691914 +VERTEX_SE3:QUAT 997 -26.4999 -27.7321 -55.9857 0.596207 -0.36304 0.0725103 0.712378 +VERTEX_SE3:QUAT 998 -22.2437 -29.2742 -52.3545 0.585122 -0.329017 0.113256 0.732498 +VERTEX_SE3:QUAT 999 -17.6122 -30.3322 -48.6843 0.567673 -0.291977 0.161285 0.752651 +VERTEX_SE3:QUAT 1000 -12.8642 -30.2331 -44.9203 0.556042 -0.248447 0.205063 0.766185 +VERTEX_SE3:QUAT 1001 -8.20101 -29.8131 -41.3703 0.532002 -0.21716 0.271234 0.772171 +VERTEX_SE3:QUAT 1002 -3.75674 -28.4537 -37.5532 0.512845 -0.173474 0.315717 0.779243 +VERTEX_SE3:QUAT 1003 0.617816 -26.3679 -34.0955 0.480293 -0.153034 0.375467 0.777769 +VERTEX_SE3:QUAT 1004 4.40687 -23.4124 -30.8108 0.456286 -0.105812 0.40938 0.782953 +VERTEX_SE3:QUAT 1005 8.10621 -19.7899 -27.6738 0.439149 -0.0596834 0.426314 0.78857 +VERTEX_SE3:QUAT 1006 11.6495 -15.6861 -25.3171 0.409422 -0.036813 0.493058 0.766754 +VERTEX_SE3:QUAT 1007 14.5061 -11.2198 -22.8497 0.379981 0.00204544 0.534925 0.754629 +VERTEX_SE3:QUAT 1008 16.8277 -6.01963 -20.7664 0.352437 0.0301846 0.59156 0.724523 +VERTEX_SE3:QUAT 1009 18.3701 -0.691157 -18.815 0.322342 0.066187 0.625478 0.707454 +VERTEX_SE3:QUAT 1010 19.5812 5.03895 -17.1447 0.285196 0.109373 0.641732 0.703478 +VERTEX_SE3:QUAT 1011 20.1957 10.8553 -16.164 0.251239 0.147117 0.673012 0.679919 +VERTEX_SE3:QUAT 1012 20.2574 16.7501 -15.6218 0.212898 0.189381 0.689138 0.666257 +VERTEX_SE3:QUAT 1013 19.9574 22.9144 -15.6385 0.172468 0.232275 0.702093 0.650668 +VERTEX_SE3:QUAT 1014 18.9605 28.91 -16.4829 0.143423 0.262943 0.721449 0.624341 +VERTEX_SE3:QUAT 1015 17.6386 34.9825 -17.3603 0.114792 0.296091 0.746525 0.584683 +VERTEX_SE3:QUAT 1016 15.7034 40.6542 -18.5701 0.0739639 0.331265 0.75693 0.558435 +VERTEX_SE3:QUAT 1017 13.286 45.8485 -20.3074 0.0285082 0.355443 0.774855 0.521965 +VERTEX_SE3:QUAT 1018 10.3196 50.7339 -22.7136 -0.0145089 0.391517 0.785998 0.478238 +VERTEX_SE3:QUAT 1019 7.10865 54.9628 -25.2145 -0.0488834 0.412513 0.809502 0.414909 +VERTEX_SE3:QUAT 1020 3.13266 58.498 -28.0211 -0.104544 0.434967 0.803794 0.392159 +VERTEX_SE3:QUAT 1021 -0.903613 61.5089 -31.1831 -0.127897 0.459273 0.819892 0.317 +VERTEX_SE3:QUAT 1022 -5.73176 63.7243 -34.1732 -0.182795 0.473382 0.809482 0.295354 +VERTEX_SE3:QUAT 1023 -10.4189 65.1282 -37.7299 -0.238078 0.490198 0.792618 0.273461 +VERTEX_SE3:QUAT 1024 -14.888 65.9431 -41.6715 -0.261339 0.511417 0.791302 0.20975 +VERTEX_SE3:QUAT 1025 -19.6015 65.8846 -45.4912 -0.28992 0.524157 0.785324 0.156437 +VERTEX_SE3:QUAT 1026 -24.2366 65.0702 -49.2393 -0.334239 0.531748 0.767526 0.128189 +VERTEX_SE3:QUAT 1027 -28.6407 63.6286 -53.2844 -0.368599 0.553588 0.74167 0.0871821 +VERTEX_SE3:QUAT 1028 -33.0449 61.8692 -57.2736 -0.425777 0.548326 0.716869 0.0644293 +VERTEX_SE3:QUAT 1029 -36.5346 59.2994 -61.5182 -0.445815 0.566266 0.69319 0.00896176 +VERTEX_SE3:QUAT 1030 -40.0259 55.8648 -65.1528 -0.465539 0.575864 0.670825 -0.0405987 +VERTEX_SE3:QUAT 1031 -43.0776 52.0053 -68.5613 -0.495948 0.575962 0.644274 -0.0849361 +VERTEX_SE3:QUAT 1032 -45.915 47.6908 -72.0493 -0.542622 0.569469 0.606282 -0.116998 +VERTEX_SE3:QUAT 1033 -47.7613 42.9432 -75.1087 -0.556675 0.57168 0.577606 -0.172237 +VERTEX_SE3:QUAT 1034 -49.334 37.7077 -77.5248 -0.592649 0.560994 0.542061 -0.200555 +VERTEX_SE3:QUAT 1035 -50.4147 32.2008 -80.094 -0.608282 0.565798 0.492701 -0.259057 +VERTEX_SE3:QUAT 1036 -50.8162 26.3305 -81.9158 -0.647094 0.540703 0.457803 -0.28165 +VERTEX_SE3:QUAT 1037 -50.6462 20.6552 -83.2993 -0.662773 0.541429 0.407034 -0.319234 +VERTEX_SE3:QUAT 1038 -49.8825 14.537 -84.3113 -0.661285 0.554671 0.350303 -0.363772 +VERTEX_SE3:QUAT 1039 -48.5647 8.60417 -84.5043 -0.657423 0.557185 0.294272 -0.413213 +VERTEX_SE3:QUAT 1040 -47.0253 2.73266 -83.9397 -0.682612 0.529026 0.245999 -0.440064 +VERTEX_SE3:QUAT 1041 -44.8398 -2.96248 -82.9058 -0.677938 0.530032 0.183119 -0.475324 +VERTEX_SE3:QUAT 1042 -42.3335 -8.15318 -81.0847 -0.677508 0.509901 0.131196 -0.513587 +VERTEX_SE3:QUAT 1043 -39.3759 -12.8888 -78.621 -0.681439 0.484069 0.0812592 -0.542877 +VERTEX_SE3:QUAT 1044 -36.0607 -17.1049 -76.0902 -0.671981 0.466779 0.0260115 -0.574354 +VERTEX_SE3:QUAT 1045 -32.3823 -20.9401 -73.0449 -0.671722 0.436123 -0.020674 -0.598464 +VERTEX_SE3:QUAT 1046 -28.5509 -24.0755 -69.501 -0.650976 0.421296 -0.0890797 -0.625144 +VERTEX_SE3:QUAT 1047 -24.5283 -26.6209 -65.4425 -0.628874 0.405556 -0.161301 -0.643447 +VERTEX_SE3:QUAT 1048 -20.639 -28.1989 -60.9408 -0.596367 0.380738 -0.2294 -0.668402 +VERTEX_SE3:QUAT 1049 -16.8231 -28.8842 -56.0104 -0.585651 0.334336 -0.252296 -0.693958 +VERTEX_SE3:QUAT 1050 -12.7926 -28.7454 -51.2917 -0.567659 0.303395 -0.305276 -0.701798 +VERTEX_SE3:QUAT 1051 -8.85983 -28.0417 -46.8226 -0.536596 0.269057 -0.349017 -0.719625 +VERTEX_SE3:QUAT 1052 -5.10735 -26.3643 -42.1447 -0.502135 0.241843 -0.409041 -0.722535 +VERTEX_SE3:QUAT 1053 -1.82283 -24.0239 -37.9182 -0.47712 0.197935 -0.435148 -0.737445 +VERTEX_SE3:QUAT 1054 1.3999 -20.9304 -33.7365 -0.434866 0.179189 -0.506715 -0.722511 +VERTEX_SE3:QUAT 1055 3.94525 -17.1069 -29.8005 -0.407472 0.134838 -0.526499 -0.733883 +VERTEX_SE3:QUAT 1056 6.47482 -12.7381 -26.3414 -0.369162 0.105452 -0.57536 -0.722191 +VERTEX_SE3:QUAT 1057 8.36841 -7.86245 -23.089 -0.337855 0.0525103 -0.604572 -0.719436 +VERTEX_SE3:QUAT 1058 9.74812 -2.67693 -20.3543 -0.30177 -0.000441584 -0.630022 -0.715547 +VERTEX_SE3:QUAT 1059 10.8716 3.12471 -18.2059 -0.26731 -0.0416354 -0.660455 -0.700436 +VERTEX_SE3:QUAT 1060 11.3395 9.03039 -16.7968 -0.235766 -0.084973 -0.676495 -0.692494 +VERTEX_SE3:QUAT 1061 11.6212 15.1013 -15.9511 -0.198669 -0.118853 -0.707879 -0.667317 +VERTEX_SE3:QUAT 1062 11.0829 21.1805 -15.5415 -0.152598 -0.168734 -0.716372 -0.659586 +VERTEX_SE3:QUAT 1063 10.2632 27.3232 -15.9736 -0.118106 -0.204935 -0.731547 -0.639447 +VERTEX_SE3:QUAT 1064 9.30726 33.2069 -16.7811 -0.0772163 -0.240561 -0.757757 -0.601642 +VERTEX_SE3:QUAT 1065 7.40355 38.894 -18.1263 -0.0286277 -0.268748 -0.772728 -0.574323 +VERTEX_SE3:QUAT 1066 5.35977 44.0333 -19.9556 0.0304492 -0.308397 -0.752764 -0.580785 +VERTEX_SE3:QUAT 1067 3.26059 49.1762 -22.6469 0.0732596 -0.344787 -0.742563 -0.569522 +VERTEX_SE3:QUAT 1068 0.914808 53.852 -25.791 0.107116 -0.37472 -0.743214 -0.543824 +VERTEX_SE3:QUAT 1069 -1.47042 57.9247 -29.5796 0.149151 -0.413851 -0.739068 -0.510156 +VERTEX_SE3:QUAT 1070 -4.20238 61.533 -33.8583 0.188893 -0.446253 -0.737549 -0.470318 +VERTEX_SE3:QUAT 1071 -7.14725 64.5657 -38.3546 0.232316 -0.477344 -0.731251 -0.428303 +VERTEX_SE3:QUAT 1072 -10.286 66.6817 -43.1033 0.283499 -0.500357 -0.711059 -0.404558 +VERTEX_SE3:QUAT 1073 -13.3574 68.1779 -48.1404 0.323443 -0.525515 -0.693225 -0.372368 +VERTEX_SE3:QUAT 1074 -16.4262 68.7646 -53.3385 0.353153 -0.557125 -0.673542 -0.333519 +VERTEX_SE3:QUAT 1075 -19.9081 68.4644 -58.4134 0.38563 -0.58123 -0.655037 -0.290495 +VERTEX_SE3:QUAT 1076 -23.0428 67.5786 -63.5437 0.430133 -0.595877 -0.627294 -0.257717 +VERTEX_SE3:QUAT 1077 -26.1918 66.071 -68.8193 0.463379 -0.61046 -0.602199 -0.22355 +VERTEX_SE3:QUAT 1078 -29.0314 63.7363 -73.7813 0.484989 -0.633902 -0.575199 -0.179162 +VERTEX_SE3:QUAT 1079 -31.9487 61.0227 -78.5079 0.514743 -0.645435 -0.546764 -0.139652 +VERTEX_SE3:QUAT 1080 -34.4504 57.6518 -82.7447 0.514681 -0.67408 -0.525304 -0.0690993 +VERTEX_SE3:QUAT 1081 -37.1277 53.6305 -86.4144 0.547051 -0.673015 -0.496979 -0.0282513 +VERTEX_SE3:QUAT 1082 -39.1968 48.9087 -89.9012 0.576408 -0.671925 -0.464872 0.0128129 +VERTEX_SE3:QUAT 1083 -41.1895 43.7467 -92.8198 0.570653 -0.69353 -0.432407 0.079966 +VERTEX_SE3:QUAT 1084 -43.0481 38.3176 -94.8333 0.579268 -0.698461 -0.403067 0.118904 +VERTEX_SE3:QUAT 1085 -44.7521 32.5346 -96.2813 0.59261 -0.697071 -0.364693 0.172927 +VERTEX_SE3:QUAT 1086 -46.1128 26.4731 -97.1416 0.60586 -0.694479 -0.322158 0.216441 +VERTEX_SE3:QUAT 1087 -46.9103 20.5073 -97.3608 0.602229 -0.69377 -0.286475 0.271909 +VERTEX_SE3:QUAT 1088 -47.4534 14.5269 -96.9542 0.626388 -0.674501 -0.241948 0.306834 +VERTEX_SE3:QUAT 1089 -47.1053 8.41648 -96.0101 0.631874 -0.664313 -0.201017 0.344985 +VERTEX_SE3:QUAT 1090 -46.6191 2.39755 -94.5046 0.650031 -0.637962 -0.164188 0.378822 +VERTEX_SE3:QUAT 1091 -45.5382 -3.50392 -92.6595 0.6502 -0.626329 -0.115813 0.414174 +VERTEX_SE3:QUAT 1092 -44.2998 -9.10838 -90.0943 0.657372 -0.60174 -0.0769876 0.447039 +VERTEX_SE3:QUAT 1093 -42.5397 -14.0864 -87.176 0.646453 -0.588083 -0.0289254 0.485201 +VERTEX_SE3:QUAT 1094 -40.4529 -18.5414 -83.7489 0.614189 -0.587353 0.0421913 0.525365 +VERTEX_SE3:QUAT 1095 -38.5028 -22.4641 -79.4193 0.587785 -0.577553 0.0899021 0.559338 +VERTEX_SE3:QUAT 1096 -36.3515 -25.7141 -74.6157 0.570387 -0.550566 0.133343 0.594774 +VERTEX_SE3:QUAT 1097 -33.7518 -28.2612 -69.5305 0.561979 -0.504583 0.165294 0.634235 +VERTEX_SE3:QUAT 1098 -30.941 -30.2521 -64.6071 0.558258 -0.455647 0.183967 0.668498 +VERTEX_SE3:QUAT 1099 -27.7068 -31.4864 -59.7411 0.540026 -0.411654 0.220515 0.700205 +VERTEX_SE3:QUAT 1100 -24.0258 -31.9295 -54.6885 0.514259 -0.378388 0.272777 0.719689 +VERTEX_SE3:QUAT 1101 -20.4486 -31.6167 -49.525 0.508856 -0.330181 0.300558 0.73601 +VERTEX_SE3:QUAT 1102 -16.6361 -30.6578 -44.8433 0.465324 -0.313487 0.36011 0.745332 +VERTEX_SE3:QUAT 1103 -13.1653 -28.7903 -40.0252 0.438326 -0.27766 0.392186 0.759582 +VERTEX_SE3:QUAT 1104 -10.0129 -26.3019 -35.3633 0.408116 -0.224951 0.423092 0.777066 +VERTEX_SE3:QUAT 1105 -6.62436 -23.0528 -31.2839 0.383262 -0.172114 0.440107 0.793595 +VERTEX_SE3:QUAT 1106 -3.20021 -19.1812 -27.801 0.357685 -0.124146 0.451014 0.80823 +VERTEX_SE3:QUAT 1107 0.283836 -14.936 -24.8114 0.328485 -0.0770607 0.473387 0.813673 +VERTEX_SE3:QUAT 1108 3.5065 -10.2262 -22.3359 0.301742 -0.0329259 0.48868 0.81796 +VERTEX_SE3:QUAT 1109 6.47866 -5.33495 -20.6758 0.262528 0.00500567 0.521942 0.81156 +VERTEX_SE3:QUAT 1110 9.21995 0.0955361 -19.4936 0.227251 0.06101 0.531946 0.81343 +VERTEX_SE3:QUAT 1111 11.7058 5.86707 -18.931 0.211939 0.115151 0.54939 0.799995 +VERTEX_SE3:QUAT 1112 13.7349 11.6018 -19.0584 0.174232 0.165225 0.586929 0.773213 +VERTEX_SE3:QUAT 1113 15.1308 17.5903 -19.6872 0.143533 0.209784 0.619657 0.742572 +VERTEX_SE3:QUAT 1114 15.7553 23.645 -20.6428 0.104605 0.256358 0.616516 0.737053 +VERTEX_SE3:QUAT 1115 16.2728 29.5402 -22.6361 0.0709629 0.308705 0.621861 0.716209 +VERTEX_SE3:QUAT 1116 16.1897 35.0596 -25.0609 0.0272341 0.3474 0.631949 0.692252 +VERTEX_SE3:QUAT 1117 15.5868 40.484 -27.9486 -0.00871449 0.390252 0.647298 0.6547 +VERTEX_SE3:QUAT 1118 14.423 45.5317 -31.3131 -0.045221 0.42778 0.666453 0.608933 +VERTEX_SE3:QUAT 1119 12.533 50.1965 -35.2066 -0.0705408 0.464752 0.683005 0.559046 +VERTEX_SE3:QUAT 1120 10.1211 54.2606 -39.0512 -0.110329 0.501692 0.672859 0.532347 +VERTEX_SE3:QUAT 1121 7.66521 57.7479 -43.2767 -0.124976 0.530141 0.703323 0.456802 +VERTEX_SE3:QUAT 1122 4.21648 60.386 -47.5389 -0.16244 0.559753 0.703334 0.406954 +VERTEX_SE3:QUAT 1123 0.25825 62.533 -51.9236 -0.200222 0.591579 0.68991 0.366019 +VERTEX_SE3:QUAT 1124 -3.74439 63.892 -56.4775 -0.242226 0.621596 0.666258 0.333235 +VERTEX_SE3:QUAT 1125 -7.91 64.3761 -61.0553 -0.280921 0.639773 0.661262 0.27296 +VERTEX_SE3:QUAT 1126 -12.3099 63.8973 -65.6229 -0.316297 0.654618 0.650172 0.220697 +VERTEX_SE3:QUAT 1127 -16.6837 62.87 -70.0047 -0.323371 0.681088 0.63923 0.151443 +VERTEX_SE3:QUAT 1128 -21.1805 61.0541 -73.6528 -0.347646 0.694237 0.624067 0.0878522 +VERTEX_SE3:QUAT 1129 -25.6597 58.5525 -76.8906 -0.375784 0.704617 0.600251 0.0447157 +VERTEX_SE3:QUAT 1130 -29.9135 55.1944 -79.928 -0.414368 0.70704 0.57305 0.00281862 +VERTEX_SE3:QUAT 1131 -33.8849 51.3268 -82.8146 -0.438157 0.711182 0.54766 -0.0480414 +VERTEX_SE3:QUAT 1132 -37.3196 46.8145 -85.3049 -0.433761 0.728904 0.517988 -0.110632 +VERTEX_SE3:QUAT 1133 -40.7431 42.1236 -86.7559 -0.449063 0.731362 0.483091 -0.173422 +VERTEX_SE3:QUAT 1134 -43.8685 36.7283 -87.7102 -0.479038 0.722527 0.448528 -0.217485 +VERTEX_SE3:QUAT 1135 -46.4645 30.9928 -88.4738 -0.466767 0.729713 0.406334 -0.290758 +VERTEX_SE3:QUAT 1136 -48.7653 25.2977 -88.0017 -0.501973 0.703855 0.379862 -0.329113 +VERTEX_SE3:QUAT 1137 -50.024 19.233 -87.5472 -0.528658 0.686074 0.339365 -0.366952 +VERTEX_SE3:QUAT 1138 -50.7683 13.2814 -86.3466 -0.545503 0.664094 0.293919 -0.418351 +VERTEX_SE3:QUAT 1139 -50.7176 7.17792 -84.8081 -0.545525 0.649455 0.250106 -0.466967 +VERTEX_SE3:QUAT 1140 -50.262 1.42632 -82.5606 -0.54108 0.63114 0.210946 -0.514195 +VERTEX_SE3:QUAT 1141 -49.194 -3.8596 -79.6982 -0.545388 0.605469 0.172516 -0.553352 +VERTEX_SE3:QUAT 1142 -47.6445 -8.96233 -76.6072 -0.562662 0.562072 0.144503 -0.588732 +VERTEX_SE3:QUAT 1143 -45.2575 -13.7891 -73.3367 -0.530812 0.554742 0.0832025 -0.635277 +VERTEX_SE3:QUAT 1144 -42.4092 -17.7348 -69.3399 -0.547762 0.50357 0.0600699 -0.665406 +VERTEX_SE3:QUAT 1145 -39.1685 -21.5155 -65.564 -0.546163 0.462812 0.0232883 -0.697832 +VERTEX_SE3:QUAT 1146 -35.3475 -24.5784 -61.7291 -0.553821 0.412582 0.000711075 -0.723227 +VERTEX_SE3:QUAT 1147 -31.0535 -27.163 -58.1085 -0.553418 0.376278 -0.032997 -0.74233 +VERTEX_SE3:QUAT 1148 -26.3455 -29.0212 -54.4991 -0.537891 0.342056 -0.0855071 -0.765741 +VERTEX_SE3:QUAT 1149 -21.3813 -30.1089 -50.804 -0.519474 0.308957 -0.141424 -0.784023 +VERTEX_SE3:QUAT 1150 -16.4868 -30.3912 -46.978 -0.505245 0.272886 -0.187107 -0.797027 +VERTEX_SE3:QUAT 1151 -11.4522 -29.878 -43.0658 -0.483455 0.240178 -0.235327 -0.808212 +VERTEX_SE3:QUAT 1152 -6.47016 -28.6285 -39.2835 -0.468538 0.187993 -0.270883 -0.819606 +VERTEX_SE3:QUAT 1153 -1.62545 -26.4787 -35.931 -0.451 0.133922 -0.313621 -0.824806 +VERTEX_SE3:QUAT 1154 3.23218 -23.7229 -32.8241 -0.437073 0.0812222 -0.3503 -0.824415 +VERTEX_SE3:QUAT 1155 7.83213 -20.1894 -30.5028 -0.411283 0.0310056 -0.395991 -0.820412 +VERTEX_SE3:QUAT 1156 11.9904 -16.0333 -28.3544 -0.393284 -0.0204115 -0.406786 -0.824279 +VERTEX_SE3:QUAT 1157 16.0046 -11.4144 -26.8587 -0.36784 -0.0699708 -0.428557 -0.822275 +VERTEX_SE3:QUAT 1158 19.6568 -6.71426 -25.8626 -0.342676 -0.122968 -0.460651 -0.809477 +VERTEX_SE3:QUAT 1159 22.8453 -1.35129 -25.346 -0.308927 -0.18777 -0.464818 -0.808239 +VERTEX_SE3:QUAT 1160 25.7258 4.16982 -25.779 -0.27807 -0.22338 -0.506651 -0.78491 +VERTEX_SE3:QUAT 1161 27.8847 9.80722 -26.5246 -0.248201 -0.267855 -0.509954 -0.778844 +VERTEX_SE3:QUAT 1162 29.746 15.6668 -27.9325 -0.215498 -0.317185 -0.513532 -0.767619 +VERTEX_SE3:QUAT 1163 31.0818 21.3506 -29.9118 -0.192335 -0.36641 -0.546809 -0.727839 +VERTEX_SE3:QUAT 1164 31.5038 27.119 -32.2853 -0.151847 -0.413609 -0.560587 -0.701151 +VERTEX_SE3:QUAT 1165 31.4136 32.6836 -35.1458 -0.117604 -0.44976 -0.579988 -0.668954 +VERTEX_SE3:QUAT 1166 30.7551 37.9788 -38.3609 -0.0749981 -0.496049 -0.585949 -0.636376 +VERTEX_SE3:QUAT 1167 29.4016 42.8164 -41.9476 -0.0293119 -0.534131 -0.583831 -0.610726 +VERTEX_SE3:QUAT 1168 27.7038 47.0297 -45.9801 0.0102665 -0.568833 -0.571266 -0.59159 +VERTEX_SE3:QUAT 1169 25.6616 51.0462 -50.3675 0.0419473 -0.598542 -0.574792 -0.556419 +VERTEX_SE3:QUAT 1170 23.146 54.5524 -55.3697 0.0634396 -0.639968 -0.576534 -0.504009 +VERTEX_SE3:QUAT 1171 19.8637 57.4081 -60.068 0.0988689 -0.674074 -0.565215 -0.465168 +VERTEX_SE3:QUAT 1172 16.216 59.5071 -64.5735 0.142709 -0.699803 -0.550816 -0.43187 +VERTEX_SE3:QUAT 1173 12.479 60.7092 -69.3507 0.174245 -0.726532 -0.536331 -0.392606 +VERTEX_SE3:QUAT 1174 8.30935 61.3357 -73.9597 0.187261 -0.754631 -0.532704 -0.334203 +VERTEX_SE3:QUAT 1175 3.85043 61.6086 -78.1924 0.22347 -0.77286 -0.513421 -0.298576 +VERTEX_SE3:QUAT 1176 -0.874926 60.9637 -82.4673 0.238393 -0.795671 -0.50325 -0.238362 +VERTEX_SE3:QUAT 1177 -5.97712 59.9194 -86.4021 0.280199 -0.810971 -0.477448 -0.189362 +VERTEX_SE3:QUAT 1178 -10.8012 57.7557 -89.7299 0.306258 -0.816508 -0.470208 -0.135738 +VERTEX_SE3:QUAT 1179 -15.3032 55.218 -92.7609 0.341543 -0.824845 -0.440236 -0.0957704 +VERTEX_SE3:QUAT 1180 -19.8253 51.885 -95.2548 0.362601 -0.835316 -0.411885 -0.0334312 +VERTEX_SE3:QUAT 1181 -24.23 48.1667 -97.2855 0.387622 -0.836466 -0.387135 0.0141447 +VERTEX_SE3:QUAT 1182 -28.5039 43.6754 -98.7644 0.432736 -0.823482 -0.362673 0.055541 +VERTEX_SE3:QUAT 1183 -32.4346 38.8897 -100.032 0.463393 -0.813382 -0.335445 0.105609 +VERTEX_SE3:QUAT 1184 -35.8758 33.5336 -100.527 0.494926 -0.799657 -0.307301 0.145477 +VERTEX_SE3:QUAT 1185 -38.6373 27.9591 -100.444 0.524231 -0.783077 -0.276935 0.187828 +VERTEX_SE3:QUAT 1186 -40.6902 22.0672 -100.13 0.525814 -0.782462 -0.237575 0.23416 +VERTEX_SE3:QUAT 1187 -42.4185 16.2416 -99.1261 0.533792 -0.772491 -0.200201 0.279721 +VERTEX_SE3:QUAT 1188 -43.8844 10.3851 -97.6839 0.546866 -0.754243 -0.170109 0.321121 +VERTEX_SE3:QUAT 1189 -44.9342 4.36773 -95.5338 0.575291 -0.719724 -0.144887 0.360617 +VERTEX_SE3:QUAT 1190 -45.1655 -1.38908 -93.1835 0.575056 -0.701621 -0.10581 0.407238 +VERTEX_SE3:QUAT 1191 -45.0853 -7.02386 -90.183 0.586739 -0.670756 -0.0693573 0.448346 +VERTEX_SE3:QUAT 1192 -44.2861 -12.1121 -86.825 0.58519 -0.646355 -0.0290575 0.488807 +VERTEX_SE3:QUAT 1193 -43.0823 -16.7564 -82.8482 0.593172 -0.611306 -0.00159995 0.523879 +VERTEX_SE3:QUAT 1194 -41.2439 -21.1581 -78.7497 0.584235 -0.58584 0.0337117 0.560646 +VERTEX_SE3:QUAT 1195 -39.0491 -24.9955 -74.3345 0.567605 -0.560244 0.0824256 0.597626 +VERTEX_SE3:QUAT 1196 -36.4479 -28.1382 -69.5801 0.537488 -0.540536 0.137882 0.63239 +VERTEX_SE3:QUAT 1197 -33.7007 -30.3736 -64.385 0.505773 -0.517577 0.193424 0.662492 +VERTEX_SE3:QUAT 1198 -31.1084 -31.6606 -58.9397 0.498105 -0.476159 0.230414 0.687076 +VERTEX_SE3:QUAT 1199 -28.1825 -32.1638 -53.4207 0.481498 -0.435432 0.275126 0.709129 +VERTEX_SE3:QUAT 1200 -25.0543 -32.0584 -47.9811 0.469639 -0.373401 0.298202 0.742352 +VERTEX_SE3:QUAT 1201 -21.5767 -31.1101 -42.9131 0.449951 -0.328327 0.316851 0.767692 +VERTEX_SE3:QUAT 1202 -17.7462 -29.7981 -38.1932 0.440888 -0.253281 0.316471 0.80082 +VERTEX_SE3:QUAT 1203 -13.5347 -27.7011 -34.1153 0.420648 -0.201748 0.347504 0.813384 +VERTEX_SE3:QUAT 1204 -9.25261 -24.9107 -30.5559 0.410367 -0.143466 0.358826 0.82599 +VERTEX_SE3:QUAT 1205 -4.86093 -21.6993 -27.6147 0.374089 -0.111069 0.416327 0.821214 +VERTEX_SE3:QUAT 1206 -1.08497 -17.6694 -24.736 0.353529 -0.0573188 0.428787 0.829381 +VERTEX_SE3:QUAT 1207 2.71049 -13.1313 -22.451 0.335245 -0.00820871 0.442009 0.831968 +VERTEX_SE3:QUAT 1208 6.62128 -8.46112 -20.8356 0.314257 0.0432633 0.440943 0.839607 +VERTEX_SE3:QUAT 1209 10.3562 -3.23347 -20.0107 0.280688 0.100526 0.461801 0.835373 +VERTEX_SE3:QUAT 1210 13.7553 2.12307 -19.8865 0.248944 0.154364 0.478836 0.827596 +VERTEX_SE3:QUAT 1211 16.7685 7.5536 -20.1846 0.217138 0.197066 0.504235 0.812258 +VERTEX_SE3:QUAT 1212 19.2979 13.3549 -21.2284 0.185622 0.253367 0.506343 0.803098 +VERTEX_SE3:QUAT 1213 21.558 19.0308 -22.7516 0.151238 0.305571 0.522563 0.781461 +VERTEX_SE3:QUAT 1214 22.8049 24.5103 -24.9999 0.11993 0.352588 0.528945 0.762571 +VERTEX_SE3:QUAT 1215 23.7541 30.091 -27.9328 0.0936201 0.39391 0.53433 0.741998 +VERTEX_SE3:QUAT 1216 24.1563 35.2274 -31.4233 0.0581528 0.445888 0.523241 0.723893 +VERTEX_SE3:QUAT 1217 24.3467 40.0779 -35.2902 0.0296374 0.49377 0.53333 0.686202 +VERTEX_SE3:QUAT 1218 23.8753 44.5784 -39.503 -0.0137183 0.539581 0.521561 0.660786 +VERTEX_SE3:QUAT 1219 22.8769 48.5391 -44.3388 -0.0388462 0.582136 0.531255 0.61431 +VERTEX_SE3:QUAT 1220 21.3247 52.0956 -49.4376 -0.0900232 0.615578 0.509944 0.594068 +VERTEX_SE3:QUAT 1221 19.4 55.0053 -54.8038 -0.137228 0.649647 0.499368 0.55656 +VERTEX_SE3:QUAT 1222 17.0864 57.163 -60.2466 -0.17633 0.684792 0.472056 0.526431 +VERTEX_SE3:QUAT 1223 14.4922 58.4201 -65.7172 -0.202656 0.713927 0.463017 0.484617 +VERTEX_SE3:QUAT 1224 11.5917 59.2512 -71.2419 -0.220214 0.744956 0.455197 0.435135 +VERTEX_SE3:QUAT 1225 8.06801 59.4609 -76.4536 -0.243131 0.771823 0.440901 0.388308 +VERTEX_SE3:QUAT 1226 4.26731 59.1615 -81.5456 -0.260166 0.794651 0.431378 0.338759 +VERTEX_SE3:QUAT 1227 0.167074 57.9749 -86.1954 -0.285207 0.80932 0.423052 0.291006 +VERTEX_SE3:QUAT 1228 -3.96872 56.2803 -90.2835 -0.315223 0.828517 0.395781 0.239898 +VERTEX_SE3:QUAT 1229 -8.10795 53.9839 -94.0726 -0.359308 0.836815 0.363005 0.197145 +VERTEX_SE3:QUAT 1230 -12.3038 50.7411 -97.6118 -0.373125 0.846262 0.352752 0.14207 +VERTEX_SE3:QUAT 1231 -16.5848 47.1889 -100.442 -0.405113 0.849935 0.322926 0.0959838 +VERTEX_SE3:QUAT 1232 -20.6037 43.1043 -102.727 -0.419602 0.853451 0.306473 0.0403674 +VERTEX_SE3:QUAT 1233 -24.4982 38.5971 -104.421 -0.450109 0.850713 0.271445 -0.002591 +VERTEX_SE3:QUAT 1234 -28.2011 33.63 -105.69 -0.476384 0.844549 0.23886 -0.0523468 +VERTEX_SE3:QUAT 1235 -31.4094 28.382 -106.384 -0.497363 0.835089 0.205123 -0.114812 +VERTEX_SE3:QUAT 1236 -34.0688 22.7835 -106.184 -0.514275 0.822864 0.167683 -0.174065 +VERTEX_SE3:QUAT 1237 -36.3238 17.0841 -104.922 -0.519521 0.812488 0.133331 -0.228437 +VERTEX_SE3:QUAT 1238 -38.4187 11.4895 -103.124 -0.531091 0.794802 0.0939844 -0.278205 +VERTEX_SE3:QUAT 1239 -39.6946 5.9531 -100.743 -0.516003 0.788766 0.0585585 -0.328877 +VERTEX_SE3:QUAT 1240 -41.0854 0.596974 -97.4299 -0.535842 0.755348 0.0351905 -0.375613 +VERTEX_SE3:QUAT 1241 -41.7258 -4.45717 -93.8327 -0.532088 0.73759 0.00422448 -0.415723 +VERTEX_SE3:QUAT 1242 -42.1611 -9.36043 -89.7342 -0.556688 0.694076 -0.0164769 -0.456164 +VERTEX_SE3:QUAT 1243 -41.7967 -13.9733 -85.4001 -0.534819 0.68033 -0.0602853 -0.49748 +VERTEX_SE3:QUAT 1244 -40.9558 -18.1484 -80.8208 -0.569802 0.616143 -0.0815208 -0.537632 +VERTEX_SE3:QUAT 1245 -39.2436 -21.5771 -75.9299 -0.538425 0.601803 -0.144363 -0.571918 +VERTEX_SE3:QUAT 1246 -37.6029 -24.2862 -70.4764 -0.552395 0.54137 -0.159971 -0.613342 +VERTEX_SE3:QUAT 1247 -35.1086 -26.6711 -65.1622 -0.544388 0.500164 -0.184134 -0.647744 +VERTEX_SE3:QUAT 1248 -32.2276 -28.2007 -59.8864 -0.540418 0.444119 -0.213519 -0.681995 +VERTEX_SE3:QUAT 1249 -28.8134 -29.115 -54.7116 -0.538792 0.38143 -0.239614 -0.711899 +VERTEX_SE3:QUAT 1250 -24.8879 -29.2542 -49.7849 -0.53451 0.323766 -0.257369 -0.737046 +VERTEX_SE3:QUAT 1251 -20.6373 -28.6037 -45.3868 -0.515053 0.280709 -0.30373 -0.75078 +VERTEX_SE3:QUAT 1252 -16.422 -27.2363 -40.9346 -0.496216 0.232486 -0.33763 -0.765327 +VERTEX_SE3:QUAT 1253 -12.2356 -25.0768 -36.9868 -0.478971 0.184277 -0.366839 -0.775924 +VERTEX_SE3:QUAT 1254 -7.97676 -22.0916 -32.9998 -0.457383 0.133057 -0.395296 -0.78539 +VERTEX_SE3:QUAT 1255 -3.91885 -18.5969 -29.5923 -0.435653 0.0808529 -0.408157 -0.798171 +VERTEX_SE3:QUAT 1256 0.107541 -14.6599 -27.0668 -0.406 0.039776 -0.448284 -0.795376 +VERTEX_SE3:QUAT 1257 3.85797 -9.92366 -24.4847 -0.386833 -0.0199963 -0.457016 -0.800685 +VERTEX_SE3:QUAT 1258 7.40866 -5.0706 -22.8414 -0.358962 -0.0642434 -0.49609 -0.787981 +VERTEX_SE3:QUAT 1259 10.2868 0.621434 -21.6423 -0.316935 -0.12844 -0.492518 -0.8003 +VERTEX_SE3:QUAT 1260 13.23 6.08946 -21.3888 -0.284603 -0.186517 -0.502092 -0.795057 +VERTEX_SE3:QUAT 1261 15.7142 11.9424 -21.5907 -0.246616 -0.2429 -0.508074 -0.788696 +VERTEX_SE3:QUAT 1262 17.7561 17.8143 -22.7766 -0.208702 -0.294163 -0.512871 -0.779022 +VERTEX_SE3:QUAT 1263 19.6155 23.4449 -24.652 -0.180938 -0.334581 -0.52228 -0.763244 +VERTEX_SE3:QUAT 1264 20.8142 29.2717 -27.0156 -0.15586 -0.380503 -0.548929 -0.727738 +VERTEX_SE3:QUAT 1265 21.1719 34.7506 -29.6055 -0.112725 -0.432572 -0.536495 -0.715785 +VERTEX_SE3:QUAT 1266 21.098 39.9273 -33.2318 -0.0835747 -0.475141 -0.542144 -0.687994 +VERTEX_SE3:QUAT 1267 20.6079 44.8588 -37.057 -0.0519764 -0.52058 -0.556833 -0.645161 +VERTEX_SE3:QUAT 1268 19.463 49.5215 -41.1643 -0.0135811 -0.556544 -0.548896 -0.623529 +VERTEX_SE3:QUAT 1269 17.8651 53.7556 -45.5507 0.0273578 -0.59501 -0.545215 -0.589877 +VERTEX_SE3:QUAT 1270 15.6731 57.3632 -50.142 0.0683533 -0.629207 -0.536154 -0.558539 +VERTEX_SE3:QUAT 1271 13.2778 60.2678 -55.2964 0.0989497 -0.662612 -0.539582 -0.509908 +VERTEX_SE3:QUAT 1272 10.1236 62.5595 -60.2334 0.144684 -0.693573 -0.522213 -0.474676 +VERTEX_SE3:QUAT 1273 6.74604 64.071 -65.4117 0.194284 -0.721379 -0.495913 -0.442647 +VERTEX_SE3:QUAT 1274 3.336 64.4843 -70.5567 0.221021 -0.750345 -0.483854 -0.392451 +VERTEX_SE3:QUAT 1275 -0.50042 64.2747 -75.5624 0.268911 -0.771816 -0.462346 -0.343836 +VERTEX_SE3:QUAT 1276 -4.51274 63.368 -80.2727 0.300696 -0.786277 -0.442489 -0.309117 +VERTEX_SE3:QUAT 1277 -8.40894 61.8398 -84.8204 0.339911 -0.802149 -0.409197 -0.271248 +VERTEX_SE3:QUAT 1278 -12.251 59.4609 -88.9656 0.372219 -0.816332 -0.378883 -0.226945 +VERTEX_SE3:QUAT 1279 -16.0142 56.4568 -92.9681 0.439292 -0.807052 -0.341934 -0.196901 +VERTEX_SE3:QUAT 1280 -19.3834 52.6506 -96.4882 0.452721 -0.823797 -0.311476 -0.139229 +VERTEX_SE3:QUAT 1281 -22.7432 48.2413 -99.2796 0.484632 -0.823561 -0.279589 -0.0933261 +VERTEX_SE3:QUAT 1282 -25.7182 43.3328 -101.57 0.510113 -0.821232 -0.251498 -0.0459605 +VERTEX_SE3:QUAT 1283 -28.6034 37.7484 -103.281 0.523373 -0.825608 -0.210776 0.00503243 +VERTEX_SE3:QUAT 1284 -31.3652 32.2049 -104.124 0.559466 -0.808459 -0.176163 0.0485627 +VERTEX_SE3:QUAT 1285 -33.4604 26.3363 -104.409 0.549114 -0.817079 -0.137882 0.108828 +VERTEX_SE3:QUAT 1286 -35.6504 20.4974 -103.85 0.533279 -0.82216 -0.104006 0.169852 +VERTEX_SE3:QUAT 1287 -37.7012 14.7237 -102.391 0.534355 -0.813394 -0.0723801 0.21821 +VERTEX_SE3:QUAT 1288 -39.4327 9.03317 -100.238 0.5367 -0.798876 -0.0348297 0.269328 +VERTEX_SE3:QUAT 1289 -41.0502 3.84728 -97.295 0.548879 -0.773889 0.000808661 0.315953 +VERTEX_SE3:QUAT 1290 -41.9361 -1.21801 -94.042 0.549787 -0.751334 0.0307383 0.363712 +VERTEX_SE3:QUAT 1291 -42.4313 -5.98125 -90.1235 0.534486 -0.737556 0.0693147 0.406855 +VERTEX_SE3:QUAT 1292 -42.7553 -10.4229 -85.5189 0.551985 -0.695273 0.0858294 0.452263 +VERTEX_SE3:QUAT 1293 -42.3378 -14.5052 -81.003 0.561936 -0.649518 0.119662 0.498031 +VERTEX_SE3:QUAT 1294 -41.3173 -18.1965 -76.1382 0.571562 -0.602015 0.132772 0.54154 +VERTEX_SE3:QUAT 1295 -39.5069 -21.2475 -70.9738 0.561228 -0.568491 0.178757 0.574358 +VERTEX_SE3:QUAT 1296 -37.3719 -23.6392 -65.5683 0.552664 -0.52908 0.212446 0.607868 +VERTEX_SE3:QUAT 1297 -35.0496 -25.4581 -60.1523 0.554767 -0.47928 0.228774 0.640458 +VERTEX_SE3:QUAT 1298 -32.1511 -26.6177 -54.9061 0.544336 -0.433191 0.26119 0.669197 +VERTEX_SE3:QUAT 1299 -28.8642 -27.0398 -49.6415 0.537787 -0.376744 0.271549 0.703641 +VERTEX_SE3:QUAT 1300 -25.1055 -26.8921 -44.7061 0.53042 -0.331912 0.304825 0.718032 +VERTEX_SE3:QUAT 1301 -21.3272 -25.9797 -39.8321 0.508528 -0.284295 0.335477 0.740291 +VERTEX_SE3:QUAT 1302 -17.3016 -24.2623 -35.211 0.501988 -0.210571 0.335418 0.768871 +VERTEX_SE3:QUAT 1303 -12.867 -22.1123 -31.2854 0.472495 -0.174842 0.381782 0.774868 +VERTEX_SE3:QUAT 1304 -8.65665 -19.1744 -27.5868 0.443818 -0.123705 0.414189 0.784965 +VERTEX_SE3:QUAT 1305 -4.63232 -15.4776 -24.3143 0.419186 -0.0650783 0.434681 0.794419 +VERTEX_SE3:QUAT 1306 -0.737689 -11.1994 -21.7652 0.39174 0.0037943 0.427137 0.814911 +VERTEX_SE3:QUAT 1307 3.26694 -6.41831 -20.0768 0.356074 0.0520033 0.445878 0.819573 +VERTEX_SE3:QUAT 1308 6.93847 -1.50575 -18.9952 0.32358 0.115631 0.44426 0.82738 +VERTEX_SE3:QUAT 1309 10.4226 3.74081 -18.8862 0.29741 0.161172 0.46633 0.817379 +VERTEX_SE3:QUAT 1310 13.5624 8.97259 -19.1443 0.262867 0.212184 0.465449 0.818068 +VERTEX_SE3:QUAT 1311 16.4179 14.4296 -19.9383 0.231338 0.25653 0.497347 0.795815 +VERTEX_SE3:QUAT 1312 18.7841 20.1153 -21.2701 0.202709 0.310762 0.514761 0.772889 +VERTEX_SE3:QUAT 1313 20.3468 25.9539 -23.2214 0.162727 0.36279 0.503753 0.766901 +VERTEX_SE3:QUAT 1314 21.7062 31.3379 -26.1151 0.128267 0.410014 0.503395 0.749686 +VERTEX_SE3:QUAT 1315 22.6888 36.6146 -29.4666 0.105302 0.452577 0.528172 0.710718 +VERTEX_SE3:QUAT 1316 22.6136 41.5883 -33.0611 0.0906507 0.492341 0.56073 0.659519 +VERTEX_SE3:QUAT 1317 21.7338 46.5215 -36.7735 0.0365714 0.538841 0.546231 0.64027 +VERTEX_SE3:QUAT 1318 20.4302 50.9036 -41.0028 -0.00188428 0.580814 0.547287 0.602602 +VERTEX_SE3:QUAT 1319 18.6701 54.7736 -45.5983 -0.0145998 0.617739 0.564801 0.546979 +VERTEX_SE3:QUAT 1320 16.0075 58.325 -50.1464 -0.0543732 0.645366 0.559364 0.517357 +VERTEX_SE3:QUAT 1321 12.9277 61.1798 -54.678 -0.107349 0.673587 0.536252 0.497183 +VERTEX_SE3:QUAT 1322 9.80107 63.251 -59.6841 -0.135942 0.699776 0.525952 0.463905 +VERTEX_SE3:QUAT 1323 6.36516 64.6924 -64.693 -0.18372 0.720044 0.513387 0.429206 +VERTEX_SE3:QUAT 1324 2.60584 65.3824 -69.6597 -0.223759 0.740293 0.495723 0.395167 +VERTEX_SE3:QUAT 1325 -1.08584 65.4021 -74.6356 -0.265909 0.762473 0.47642 0.347781 +VERTEX_SE3:QUAT 1326 -4.7759 64.6106 -79.6154 -0.295534 0.78312 0.458682 0.298319 +VERTEX_SE3:QUAT 1327 -8.68926 62.9741 -84.2055 -0.338757 0.797657 0.428361 0.255919 +VERTEX_SE3:QUAT 1328 -12.5901 60.5216 -88.3601 -0.358388 0.811908 0.413336 0.203755 +VERTEX_SE3:QUAT 1329 -16.7399 57.5811 -91.9186 -0.383953 0.825677 0.385534 0.148997 +VERTEX_SE3:QUAT 1330 -20.7193 54.0225 -95.0066 -0.386336 0.843016 0.363881 0.0875135 +VERTEX_SE3:QUAT 1331 -24.8009 50.053 -97.583 -0.411247 0.845658 0.338554 0.0334703 +VERTEX_SE3:QUAT 1332 -28.7869 45.5469 -99.4162 -0.447711 0.839748 0.307106 -0.00800958 +VERTEX_SE3:QUAT 1333 -32.3243 40.6038 -101.017 -0.454521 0.845198 0.273887 -0.0635317 +VERTEX_SE3:QUAT 1334 -35.8306 35.2542 -101.474 -0.47059 0.836213 0.251818 -0.126018 +VERTEX_SE3:QUAT 1335 -38.7824 29.7837 -101.366 -0.505057 0.813157 0.234646 -0.169218 +VERTEX_SE3:QUAT 1336 -41.2113 23.8435 -100.731 -0.528364 0.795563 0.20136 -0.217634 +VERTEX_SE3:QUAT 1337 -43.0188 17.9115 -99.585 -0.560942 0.767226 0.174622 -0.257323 +VERTEX_SE3:QUAT 1338 -44.2543 11.8938 -98.1508 -0.596427 0.727582 0.144167 -0.306781 +VERTEX_SE3:QUAT 1339 -44.3904 6.01582 -96.4011 -0.587306 0.719618 0.10646 -0.354808 +VERTEX_SE3:QUAT 1340 -44.4388 0.492446 -93.9699 -0.57849 0.703814 0.0633368 -0.40741 +VERTEX_SE3:QUAT 1341 -44.0265 -4.76699 -90.606 -0.604627 0.657541 0.0405462 -0.447685 +VERTEX_SE3:QUAT 1342 -42.8446 -9.78588 -87.0308 -0.586587 0.643359 0.00250334 -0.491933 +VERTEX_SE3:QUAT 1343 -41.4967 -14.4454 -82.928 -0.553266 0.634244 -0.0542966 -0.537293 +VERTEX_SE3:QUAT 1344 -39.8793 -18.1905 -78.192 -0.529443 0.613187 -0.0991969 -0.577799 +VERTEX_SE3:QUAT 1345 -38.2182 -21.2405 -73.0948 -0.526061 0.564858 -0.124988 -0.623356 +VERTEX_SE3:QUAT 1346 -35.9171 -23.7055 -68.0586 -0.524627 0.514906 -0.140865 -0.663171 +VERTEX_SE3:QUAT 1347 -32.8571 -25.5608 -62.6394 -0.517519 0.470372 -0.177064 -0.692512 +VERTEX_SE3:QUAT 1348 -29.5734 -26.6982 -57.447 -0.521624 0.412991 -0.192553 -0.721298 +VERTEX_SE3:QUAT 1349 -25.6467 -27.2032 -52.7134 -0.51455 0.361311 -0.214005 -0.747592 +VERTEX_SE3:QUAT 1350 -21.5141 -27.1933 -48.0119 -0.504072 0.31334 -0.248439 -0.765511 +VERTEX_SE3:QUAT 1351 -16.9857 -26.4536 -43.5868 -0.496549 0.266725 -0.274969 -0.778902 +VERTEX_SE3:QUAT 1352 -12.3313 -25.0292 -39.4833 -0.488078 0.194984 -0.269142 -0.807046 +VERTEX_SE3:QUAT 1353 -7.43051 -23.2282 -36.1698 -0.470168 0.122711 -0.284208 -0.826505 +VERTEX_SE3:QUAT 1354 -2.35315 -20.7849 -33.5558 -0.457321 0.0439034 -0.277416 -0.843783 +VERTEX_SE3:QUAT 1355 2.87356 -17.9081 -31.7944 -0.437829 -0.0107997 -0.315542 -0.841797 +VERTEX_SE3:QUAT 1356 7.52197 -14.2423 -30.5636 -0.416808 -0.0560798 -0.350031 -0.837021 +VERTEX_SE3:QUAT 1357 12.0653 -10.0691 -29.7845 -0.387446 -0.115883 -0.37154 -0.835712 +VERTEX_SE3:QUAT 1358 16.2926 -5.34946 -29.5787 -0.358767 -0.17172 -0.397888 -0.826731 +VERTEX_SE3:QUAT 1359 19.8742 -0.322231 -29.8594 -0.331118 -0.230949 -0.419179 -0.813211 +VERTEX_SE3:QUAT 1360 23.0305 4.92963 -30.7 -0.301822 -0.275052 -0.460703 -0.788037 +VERTEX_SE3:QUAT 1361 25.2662 10.7126 -31.9974 -0.265942 -0.335697 -0.459131 -0.778319 +VERTEX_SE3:QUAT 1362 27.2442 16.2182 -34.0368 -0.234403 -0.383568 -0.478993 -0.753987 +VERTEX_SE3:QUAT 1363 28.7854 21.7885 -36.7222 -0.199945 -0.431091 -0.478375 -0.738471 +VERTEX_SE3:QUAT 1364 29.5025 27.0704 -39.8954 -0.16756 -0.484153 -0.46884 -0.71952 +VERTEX_SE3:QUAT 1365 29.776 32.1376 -43.6998 -0.13355 -0.529705 -0.47367 -0.690806 +VERTEX_SE3:QUAT 1366 29.576 36.9735 -47.77 -0.110296 -0.56613 -0.481475 -0.659935 +VERTEX_SE3:QUAT 1367 28.7208 41.3928 -51.9987 -0.0674152 -0.60624 -0.475778 -0.633691 +VERTEX_SE3:QUAT 1368 27.4607 45.3226 -56.4422 -0.039266 -0.636676 -0.491961 -0.592517 +VERTEX_SE3:QUAT 1369 25.3413 48.9689 -60.8508 0.00918215 -0.670408 -0.476664 -0.56856 +VERTEX_SE3:QUAT 1370 22.8831 51.9162 -65.6304 0.0432035 -0.701039 -0.465442 -0.538555 +VERTEX_SE3:QUAT 1371 20.2672 54.1923 -70.8189 0.0454605 -0.735801 -0.478576 -0.476965 +VERTEX_SE3:QUAT 1372 16.7654 55.9937 -75.4619 0.0694367 -0.76478 -0.480591 -0.423464 +VERTEX_SE3:QUAT 1373 12.8235 57.5633 -79.8636 0.109929 -0.793986 -0.464866 -0.376034 +VERTEX_SE3:QUAT 1374 8.37036 58.0597 -84.2431 0.122247 -0.818876 -0.460938 -0.319426 +VERTEX_SE3:QUAT 1375 3.5256 58.31 -88.2147 0.155935 -0.840864 -0.446683 -0.262882 +VERTEX_SE3:QUAT 1376 -1.35767 57.6146 -91.7503 0.205822 -0.846694 -0.434561 -0.227824 +VERTEX_SE3:QUAT 1377 -6.16731 56.2891 -95.0876 0.264735 -0.852745 -0.407457 -0.191624 +VERTEX_SE3:QUAT 1378 -11.0959 54.0513 -98.239 0.285625 -0.865597 -0.390099 -0.130322 +VERTEX_SE3:QUAT 1379 -15.8549 51.2773 -100.995 0.32279 -0.866456 -0.371561 -0.0836859 +VERTEX_SE3:QUAT 1380 -20.3946 47.7499 -103.323 0.375575 -0.859898 -0.343266 -0.0410768 +VERTEX_SE3:QUAT 1381 -24.733 43.6112 -105.129 0.390905 -0.861212 -0.324696 0.0088831 +VERTEX_SE3:QUAT 1382 -28.7669 39.1562 -106.405 0.419249 -0.858132 -0.291041 0.0559918 +VERTEX_SE3:QUAT 1383 -32.2303 34.2978 -107.179 0.476239 -0.833583 -0.2634 0.0946357 +VERTEX_SE3:QUAT 1384 -35.3288 28.7387 -107.509 0.496955 -0.82561 -0.229495 0.136879 +VERTEX_SE3:QUAT 1385 -37.9909 23.1262 -107.072 0.511927 -0.814691 -0.197339 0.187795 +VERTEX_SE3:QUAT 1386 -40.2616 17.539 -106.036 0.505792 -0.810818 -0.15717 0.249091 +VERTEX_SE3:QUAT 1387 -41.9896 11.9806 -104.229 0.529034 -0.7876 -0.123836 0.290643 +VERTEX_SE3:QUAT 1388 -43.3563 6.1437 -101.862 0.555727 -0.755914 -0.0990343 0.331594 +VERTEX_SE3:QUAT 1389 -44.147 0.425705 -99.2239 0.568129 -0.727176 -0.0634381 0.380027 +VERTEX_SE3:QUAT 1390 -44.322 -4.91366 -96.1262 0.596505 -0.679783 -0.0450751 0.424319 +VERTEX_SE3:QUAT 1391 -43.5526 -10.0058 -92.9518 0.609838 -0.637627 -0.0192263 0.470277 +VERTEX_SE3:QUAT 1392 -42.1167 -15.0334 -89.315 0.602442 -0.618728 0.0187642 0.503873 +VERTEX_SE3:QUAT 1393 -40.2217 -19.4191 -85.259 0.628882 -0.555657 0.0382499 0.542485 +VERTEX_SE3:QUAT 1394 -37.5822 -23.3291 -81.1955 0.624885 -0.516107 0.0740957 0.581087 +VERTEX_SE3:QUAT 1395 -34.4018 -26.3903 -76.9784 0.625204 -0.474834 0.111029 0.609365 +VERTEX_SE3:QUAT 1396 -31.1474 -28.8656 -72.4771 0.60231 -0.446977 0.159661 0.641827 +VERTEX_SE3:QUAT 1397 -27.5214 -30.6414 -67.6455 0.581004 -0.409632 0.207524 0.671989 +VERTEX_SE3:QUAT 1398 -23.7189 -31.503 -62.8041 0.583681 -0.341071 0.229636 0.700181 +VERTEX_SE3:QUAT 1399 -19.5758 -31.6998 -58.3272 0.583096 -0.284199 0.251528 0.718306 +VERTEX_SE3:QUAT 1400 -14.9966 -31.1446 -54.1758 0.576095 -0.229549 0.272649 0.735585 +VERTEX_SE3:QUAT 1401 -10.4198 -30.1559 -50.4287 0.554864 -0.191891 0.323159 0.742207 +VERTEX_SE3:QUAT 1402 -6.05333 -28.2266 -46.6829 0.540545 -0.151795 0.346686 0.751384 +VERTEX_SE3:QUAT 1403 -1.62489 -25.5946 -43.1616 0.518989 -0.0970394 0.382932 0.758022 +VERTEX_SE3:QUAT 1404 2.6535 -22.2944 -40.0644 0.4911 -0.0543205 0.417745 0.762469 +VERTEX_SE3:QUAT 1405 6.57641 -18.4244 -37.2237 0.4676 -0.000641832 0.443723 0.7645 +VERTEX_SE3:QUAT 1406 10.127 -13.853 -34.9831 0.444861 0.0523851 0.457314 0.768257 +VERTEX_SE3:QUAT 1407 13.6307 -9.08923 -33.225 0.418726 0.115543 0.466696 0.770398 +VERTEX_SE3:QUAT 1408 16.8443 -3.7982 -32.3468 0.386385 0.154385 0.503493 0.75721 +VERTEX_SE3:QUAT 1409 19.4129 1.72977 -31.7062 0.347631 0.208432 0.525859 0.747784 +VERTEX_SE3:QUAT 1410 21.4612 7.54206 -31.6616 0.305709 0.267491 0.518398 0.752498 +VERTEX_SE3:QUAT 1411 23.2173 13.3075 -32.6601 0.271517 0.314973 0.517398 0.747911 +VERTEX_SE3:QUAT 1412 24.7567 19.2321 -34.088 0.232921 0.373836 0.509842 0.738955 +VERTEX_SE3:QUAT 1413 25.6319 25.0623 -36.2225 0.206417 0.419145 0.528136 0.709071 +VERTEX_SE3:QUAT 1414 25.8604 30.7091 -38.9743 0.15867 0.468255 0.515495 0.699876 +VERTEX_SE3:QUAT 1415 25.8401 35.851 -42.2885 0.119722 0.518558 0.502976 0.681013 +VERTEX_SE3:QUAT 1416 25.2103 40.7297 -46.0746 0.0788496 0.567851 0.498394 0.650331 +VERTEX_SE3:QUAT 1417 24.2583 44.9563 -50.2019 0.0242368 0.603433 0.49034 0.628369 +VERTEX_SE3:QUAT 1418 22.7265 48.6547 -54.928 -0.00182334 0.642001 0.485884 0.593083 +VERTEX_SE3:QUAT 1419 20.512 51.8988 -59.8283 -0.0750974 0.675205 0.437512 0.589102 +VERTEX_SE3:QUAT 1420 18.4333 54.1635 -65.2816 -0.108705 0.706889 0.431994 0.549429 +VERTEX_SE3:QUAT 1421 16.0152 55.8308 -70.7946 -0.145706 0.739656 0.414838 0.509498 +VERTEX_SE3:QUAT 1422 13.13 56.6832 -76.2138 -0.164626 0.772058 0.398136 0.46724 +VERTEX_SE3:QUAT 1423 9.84854 56.8833 -81.3796 -0.192808 0.800292 0.378137 0.423521 +VERTEX_SE3:QUAT 1424 6.21408 56.5292 -86.4486 -0.249554 0.817165 0.353464 0.380825 +VERTEX_SE3:QUAT 1425 2.57906 55.2339 -91.0133 -0.283652 0.837755 0.325199 0.334595 +VERTEX_SE3:QUAT 1426 -1.15031 53.1753 -95.3487 -0.304632 0.858527 0.303885 0.278899 +VERTEX_SE3:QUAT 1427 -5.08674 50.8801 -99.2002 -0.34267 0.867465 0.279151 0.228377 +VERTEX_SE3:QUAT 1428 -9.12337 47.7077 -102.672 -0.393018 0.864651 0.249592 0.18873 +VERTEX_SE3:QUAT 1429 -12.9399 43.8749 -105.501 -0.430154 0.866178 0.207181 0.14758 +VERTEX_SE3:QUAT 1430 -16.4943 39.411 -107.99 -0.442159 0.875537 0.176594 0.0821314 +VERTEX_SE3:QUAT 1431 -20.046 34.5988 -109.43 -0.448236 0.882399 0.139343 0.0322555 +VERTEX_SE3:QUAT 1432 -23.4007 29.7106 -110.387 -0.505307 0.855763 0.109627 -0.0177747 +VERTEX_SE3:QUAT 1433 -26.0953 24.2342 -110.473 -0.537043 0.838356 0.0707002 -0.0611978 +VERTEX_SE3:QUAT 1434 -28.5674 18.4025 -109.967 -0.534467 0.836607 0.0431648 -0.112118 +VERTEX_SE3:QUAT 1435 -30.7894 12.7796 -108.736 -0.563614 0.81152 0.00949887 -0.153896 +VERTEX_SE3:QUAT 1436 -32.3562 7.13453 -107.024 -0.566269 0.796626 -0.0189614 -0.210635 +VERTEX_SE3:QUAT 1437 -33.7878 1.60762 -104.657 -0.545095 0.795532 -0.0534033 -0.259129 +VERTEX_SE3:QUAT 1438 -35.1479 -3.64677 -101.589 -0.527299 0.786014 -0.0959347 -0.308115 +VERTEX_SE3:QUAT 1439 -36.4906 -8.22461 -97.6168 -0.503556 0.775319 -0.132258 -0.357518 +VERTEX_SE3:QUAT 1440 -37.6557 -12.1548 -93.3408 -0.544685 0.718074 -0.139835 -0.410041 +VERTEX_SE3:QUAT 1441 -37.9656 -15.8812 -88.3771 -0.544165 0.690497 -0.173028 -0.444027 +VERTEX_SE3:QUAT 1442 -37.7442 -19.4452 -83.3863 -0.526794 0.66987 -0.210859 -0.478853 +VERTEX_SE3:QUAT 1443 -37.398 -22.3906 -78.0204 -0.525569 0.626516 -0.235518 -0.525153 +VERTEX_SE3:QUAT 1444 -36.4167 -24.6052 -72.2839 -0.511837 0.594134 -0.26853 -0.559392 +VERTEX_SE3:QUAT 1445 -35.1939 -26.2899 -66.5435 -0.514821 0.5438 -0.274109 -0.603412 +VERTEX_SE3:QUAT 1446 -33.4288 -27.5293 -60.9278 -0.509136 0.496652 -0.304337 -0.633638 +VERTEX_SE3:QUAT 1447 -31.2004 -27.9648 -55.1478 -0.495008 0.447845 -0.332398 -0.666269 +VERTEX_SE3:QUAT 1448 -28.6519 -27.7639 -49.6263 -0.467341 0.413791 -0.374713 -0.685536 +VERTEX_SE3:QUAT 1449 -26.1616 -26.778 -44.1624 -0.44044 0.375838 -0.405595 -0.707285 +VERTEX_SE3:QUAT 1450 -23.6155 -25.0422 -38.9437 -0.402853 0.34111 -0.44067 -0.72606 +VERTEX_SE3:QUAT 1451 -21.2314 -22.4609 -33.972 -0.395932 0.287532 -0.444064 -0.75058 +VERTEX_SE3:QUAT 1452 -18.3791 -19.4817 -29.4296 -0.366183 0.2392 -0.48345 -0.758267 +VERTEX_SE3:QUAT 1453 -15.8058 -15.8695 -25.2738 -0.319972 0.195573 -0.532866 -0.758566 +VERTEX_SE3:QUAT 1454 -13.3528 -11.6621 -21.6925 -0.298964 0.131693 -0.524138 -0.786484 +VERTEX_SE3:QUAT 1455 -10.7976 -7.05126 -18.8754 -0.274614 0.0847929 -0.529793 -0.797945 +VERTEX_SE3:QUAT 1456 -8.04348 -2.01761 -16.6113 -0.245786 0.0261469 -0.501501 -0.829097 +VERTEX_SE3:QUAT 1457 -4.85892 3.22648 -15.2013 -0.220392 -0.028801 -0.499594 -0.837259 +VERTEX_SE3:QUAT 1458 -1.84342 8.45045 -14.5554 -0.189481 -0.0936554 -0.496849 -0.841705 +VERTEX_SE3:QUAT 1459 0.991486 13.6229 -14.6751 -0.153202 -0.156869 -0.481419 -0.848621 +VERTEX_SE3:QUAT 1460 3.96013 18.8793 -15.884 -0.121705 -0.207864 -0.503637 -0.829657 +VERTEX_SE3:QUAT 1461 6.21763 24.2516 -17.5841 -0.0918129 -0.261046 -0.509342 -0.81486 +VERTEX_SE3:QUAT 1462 8.1694 29.5107 -20.0777 -0.0658209 -0.307912 -0.522464 -0.792394 +VERTEX_SE3:QUAT 1463 9.69969 34.5388 -22.9859 -0.0356895 -0.353969 -0.53072 -0.769265 +VERTEX_SE3:QUAT 1464 10.6692 39.4149 -26.4908 0.0121626 -0.397252 -0.496267 -0.771856 +VERTEX_SE3:QUAT 1465 11.668 43.7237 -30.6529 0.0567177 -0.435963 -0.475312 -0.762101 +VERTEX_SE3:QUAT 1466 12.6199 47.3235 -35.1162 0.0761188 -0.476059 -0.48312 -0.730868 +VERTEX_SE3:QUAT 1467 13.1478 50.7543 -40.1029 0.12764 -0.514441 -0.446345 -0.720995 +VERTEX_SE3:QUAT 1468 13.473 53.5411 -45.5746 0.161883 -0.563737 -0.428073 -0.687567 +VERTEX_SE3:QUAT 1469 13.3235 55.652 -51.0702 0.212031 -0.603783 -0.377197 -0.669486 +VERTEX_SE3:QUAT 1470 13.1284 56.9451 -57.0985 0.232958 -0.6412 -0.356269 -0.638487 +VERTEX_SE3:QUAT 1471 12.3774 57.2472 -63.1013 0.240283 -0.676412 -0.360237 -0.595786 +VERTEX_SE3:QUAT 1472 11.1022 57.6473 -68.9403 0.2539 -0.717576 -0.348065 -0.547238 +VERTEX_SE3:QUAT 1473 9.35947 57.2579 -74.7269 0.299239 -0.740422 -0.314814 -0.512955 +VERTEX_SE3:QUAT 1474 7.38259 56.0529 -80.4562 0.355563 -0.752685 -0.271245 -0.483184 +VERTEX_SE3:QUAT 1475 5.82044 54.0402 -85.9821 0.371972 -0.77394 -0.257506 -0.443107 +VERTEX_SE3:QUAT 1476 3.72547 51.6496 -91.3008 0.390561 -0.794343 -0.228077 -0.405539 +VERTEX_SE3:QUAT 1477 1.51842 48.4662 -95.9637 0.423388 -0.806834 -0.18497 -0.368169 +VERTEX_SE3:QUAT 1478 -0.562238 44.8526 -100.292 0.453971 -0.81639 -0.149272 -0.324247 +VERTEX_SE3:QUAT 1479 -3.04376 40.7667 -103.988 0.478126 -0.828626 -0.107148 -0.270729 +VERTEX_SE3:QUAT 1480 -5.51532 35.9632 -106.999 0.493325 -0.83763 -0.0711465 -0.223484 +VERTEX_SE3:QUAT 1481 -7.90614 31.0677 -109.312 0.489174 -0.854145 -0.0414109 -0.171549 +VERTEX_SE3:QUAT 1482 -10.5154 25.9221 -110.949 0.468236 -0.875331 -0.00735472 -0.120405 +VERTEX_SE3:QUAT 1483 -13.5933 21.0147 -112.049 0.497658 -0.864087 0.0224509 -0.0720111 +VERTEX_SE3:QUAT 1484 -16.5337 15.6947 -112.313 0.531699 -0.844628 0.0604527 -0.015679 +VERTEX_SE3:QUAT 1485 -19.0644 10.0901 -111.78 0.564976 -0.819148 0.0936099 0.0321865 +VERTEX_SE3:QUAT 1486 -21.0945 4.47615 -110.473 0.578135 -0.801369 0.130172 0.0813801 +VERTEX_SE3:QUAT 1487 -23.0881 -0.814834 -108.396 0.578476 -0.787467 0.171306 0.126161 +VERTEX_SE3:QUAT 1488 -24.6181 -5.65145 -105.935 0.587172 -0.764972 0.199166 0.174297 +VERTEX_SE3:QUAT 1489 -26.1767 -10.499 -102.636 0.573443 -0.753914 0.229671 0.223669 +VERTEX_SE3:QUAT 1490 -27.3494 -15.0923 -98.6659 0.572058 -0.726066 0.258834 0.280328 +VERTEX_SE3:QUAT 1491 -28.3389 -19.0371 -94.1025 0.554341 -0.709796 0.296691 0.317601 +VERTEX_SE3:QUAT 1492 -29.3327 -22.4096 -89.3798 0.539452 -0.68444 0.322938 0.369113 +VERTEX_SE3:QUAT 1493 -29.9457 -25.2553 -84.0432 0.521066 -0.660763 0.346574 0.414449 +VERTEX_SE3:QUAT 1494 -30.2092 -27.4118 -78.5222 0.546092 -0.601751 0.352611 0.464052 +VERTEX_SE3:QUAT 1495 -29.7245 -28.9862 -72.7242 0.538005 -0.561017 0.377407 0.503363 +VERTEX_SE3:QUAT 1496 -29.0056 -29.8557 -66.7485 0.54279 -0.500017 0.384329 0.554666 +VERTEX_SE3:QUAT 1497 -27.4703 -30.1894 -60.9614 0.539996 -0.449225 0.394354 0.592525 +VERTEX_SE3:QUAT 1498 -25.6935 -29.8764 -55.1869 0.527023 -0.402841 0.410846 0.625437 +VERTEX_SE3:QUAT 1499 -23.3852 -28.9886 -49.764 0.506349 -0.364191 0.429478 0.653088 +VERTEX_SE3:QUAT 1500 -21.0326 -27.6065 -44.47 0.485497 -0.322926 0.450459 0.676091 +VERTEX_SE3:QUAT 1501 -18.5688 -25.6711 -39.3664 0.479474 -0.245085 0.435448 0.721403 +VERTEX_SE3:QUAT 1502 -15.4746 -23.2261 -34.851 0.453911 -0.206043 0.46644 0.730715 +VERTEX_SE3:QUAT 1503 -12.4015 -19.9041 -30.6421 0.423585 -0.141598 0.474208 0.758718 +VERTEX_SE3:QUAT 1504 -9.29958 -16.0353 -27.316 0.393135 -0.0823741 0.484744 0.77697 +VERTEX_SE3:QUAT 1505 -6.2314 -11.7282 -24.7073 0.361193 -0.034312 0.493393 0.790522 +VERTEX_SE3:QUAT 1506 -3.28495 -7.0252 -22.7824 0.339085 0.0326082 0.49231 0.800993 +VERTEX_SE3:QUAT 1507 -0.278423 -2.09519 -21.6072 0.306183 0.0836962 0.502766 0.804036 +VERTEX_SE3:QUAT 1508 2.7549 3.08214 -20.8494 0.28034 0.127936 0.518696 0.797494 +VERTEX_SE3:QUAT 1509 5.30652 8.43913 -20.8384 0.240523 0.188853 0.494233 0.813767 +VERTEX_SE3:QUAT 1510 7.84268 13.646 -21.9182 0.202254 0.246151 0.497836 0.806636 +VERTEX_SE3:QUAT 1511 9.98985 18.8113 -23.4417 0.184963 0.28829 0.501589 0.794409 +VERTEX_SE3:QUAT 1512 12.0234 24.0801 -25.2394 0.143703 0.34571 0.475562 0.796037 +VERTEX_SE3:QUAT 1513 13.644 29.1754 -28.0311 0.115231 0.393691 0.485704 0.771895 +VERTEX_SE3:QUAT 1514 14.8377 34.0198 -31.311 0.0878505 0.436345 0.483911 0.753469 +VERTEX_SE3:QUAT 1515 15.562 38.6369 -35.234 0.0580928 0.478236 0.484125 0.730437 +VERTEX_SE3:QUAT 1516 15.8757 43.0664 -39.2504 0.0231052 0.524456 0.470089 0.709527 +VERTEX_SE3:QUAT 1517 15.6708 46.8477 -43.7606 0.00642091 0.563671 0.472901 0.677199 +VERTEX_SE3:QUAT 1518 15.1374 50.3449 -48.5291 -0.0250139 0.601199 0.473742 0.643041 +VERTEX_SE3:QUAT 1519 13.8439 53.4918 -53.4976 -0.057534 0.642206 0.471344 0.601744 +VERTEX_SE3:QUAT 1520 12.0412 56.1042 -58.5567 -0.0958356 0.678355 0.453595 0.570001 +VERTEX_SE3:QUAT 1521 10.0261 58.0309 -63.6824 -0.143277 0.70667 0.423724 0.548221 +VERTEX_SE3:QUAT 1522 7.94565 59.1046 -68.9493 -0.180324 0.734403 0.406872 0.512436 +VERTEX_SE3:QUAT 1523 5.47581 59.6735 -74.4704 -0.230273 0.756379 0.379292 0.480627 +VERTEX_SE3:QUAT 1524 2.81811 59.4637 -79.868 -0.27784 0.772308 0.349552 0.451839 +VERTEX_SE3:QUAT 1525 0.115617 58.2804 -84.9973 -0.307073 0.795215 0.327158 0.407807 +VERTEX_SE3:QUAT 1526 -2.63245 56.8024 -89.9123 -0.342305 0.810168 0.300365 0.369102 +VERTEX_SE3:QUAT 1527 -5.50756 54.4585 -94.4432 -0.38857 0.815028 0.267377 0.33653 +VERTEX_SE3:QUAT 1528 -8.24461 51.3479 -98.6956 -0.430476 0.82117 0.23167 0.294447 +VERTEX_SE3:QUAT 1529 -10.9288 47.6232 -102.274 -0.460384 0.828006 0.198337 0.251228 +VERTEX_SE3:QUAT 1530 -13.5694 43.4757 -105.534 -0.473847 0.837138 0.174639 0.210166 +VERTEX_SE3:QUAT 1531 -16.2128 38.9407 -108.292 -0.48438 0.849424 0.140866 0.154961 +VERTEX_SE3:QUAT 1532 -18.9365 34.0473 -110.186 -0.503677 0.848943 0.113717 0.112578 +VERTEX_SE3:QUAT 1533 -21.3623 28.8875 -111.546 -0.514459 0.851014 0.082442 0.0656583 +VERTEX_SE3:QUAT 1534 -23.9269 23.5818 -112.337 -0.537517 0.840892 0.0579955 0.02476 +VERTEX_SE3:QUAT 1535 -26.1547 18.039 -112.598 -0.588941 0.807551 0.0290417 -0.0129244 +VERTEX_SE3:QUAT 1536 -27.8109 12.4358 -112.383 -0.625566 0.778001 -0.00814217 -0.0575756 +VERTEX_SE3:QUAT 1537 -28.7917 6.61659 -111.524 -0.653297 0.748293 -0.043697 -0.10654 +VERTEX_SE3:QUAT 1538 -29.1286 0.920592 -110.078 -0.657448 0.730932 -0.0792407 -0.164991 +VERTEX_SE3:QUAT 1539 -29.4058 -4.44542 -107.749 -0.688549 0.685563 -0.114477 -0.206879 +VERTEX_SE3:QUAT 1540 -29.005 -9.41926 -104.706 -0.68719 0.666287 -0.151225 -0.246905 +VERTEX_SE3:QUAT 1541 -28.355 -13.9801 -101.44 -0.672995 0.658136 -0.195686 -0.275031 +VERTEX_SE3:QUAT 1542 -27.8709 -18.2059 -97.5842 -0.675632 0.626333 -0.231235 -0.312664 +VERTEX_SE3:QUAT 1543 -27.2195 -22.2213 -93.1778 -0.683782 0.577794 -0.263239 -0.359584 +VERTEX_SE3:QUAT 1544 -25.9321 -25.7386 -88.2304 -0.680363 0.549937 -0.28639 -0.390714 +VERTEX_SE3:QUAT 1545 -24.3977 -28.5888 -83.4049 -0.689114 0.496023 -0.311503 -0.426672 +VERTEX_SE3:QUAT 1546 -22.336 -30.8977 -78.3713 -0.687263 0.436503 -0.336326 -0.473308 +VERTEX_SE3:QUAT 1547 -19.8588 -32.0502 -73.3727 -0.665961 0.409197 -0.372199 -0.500521 +VERTEX_SE3:QUAT 1548 -17.4099 -32.8148 -68.1503 -0.640079 0.379615 -0.410861 -0.526673 +VERTEX_SE3:QUAT 1549 -14.951 -32.6094 -62.7392 -0.624563 0.337696 -0.443229 -0.547202 +VERTEX_SE3:QUAT 1550 -12.7485 -31.9351 -57.3623 -0.582339 0.324256 -0.493282 -0.558939 +VERTEX_SE3:QUAT 1551 -10.8271 -30.3488 -51.8735 -0.570917 0.256695 -0.500881 -0.597729 +VERTEX_SE3:QUAT 1552 -8.52656 -28.116 -47.0006 -0.545765 0.210551 -0.522914 -0.619976 +VERTEX_SE3:QUAT 1553 -6.16001 -25.3957 -42.5645 -0.524475 0.147361 -0.52058 -0.657424 +VERTEX_SE3:QUAT 1554 -3.59035 -22.0314 -38.5959 -0.491975 0.101307 -0.536428 -0.678191 +VERTEX_SE3:QUAT 1555 -1.15322 -17.9423 -35.0924 -0.468216 0.0415426 -0.529739 -0.705992 +VERTEX_SE3:QUAT 1556 1.39567 -13.6181 -32.0809 -0.443088 -0.0223322 -0.523807 -0.727186 +VERTEX_SE3:QUAT 1557 3.91445 -8.77292 -29.8558 -0.411562 -0.0754471 -0.537543 -0.732101 +VERTEX_SE3:QUAT 1558 6.22938 -3.65253 -28.2684 -0.378246 -0.121315 -0.546886 -0.736973 +VERTEX_SE3:QUAT 1559 8.27529 1.87174 -27.2613 -0.340728 -0.1778 -0.540801 -0.748215 +VERTEX_SE3:QUAT 1560 10.1518 7.23204 -27.126 -0.305988 -0.226607 -0.545153 -0.746879 +VERTEX_SE3:QUAT 1561 11.7073 12.7789 -27.7663 -0.269952 -0.2792 -0.532217 -0.752275 +VERTEX_SE3:QUAT 1562 12.9959 18.3478 -28.9803 -0.24405 -0.319562 -0.552592 -0.730042 +VERTEX_SE3:QUAT 1563 13.9796 23.784 -30.417 -0.209153 -0.373114 -0.541303 -0.723901 +VERTEX_SE3:QUAT 1564 14.5697 29.4168 -32.8005 -0.176046 -0.410781 -0.545346 -0.709129 +VERTEX_SE3:QUAT 1565 14.8709 34.7064 -35.4901 -0.137845 -0.459953 -0.53298 -0.696688 +VERTEX_SE3:QUAT 1566 14.7708 39.6165 -38.6685 -0.0829528 -0.499858 -0.508781 -0.69599 +VERTEX_SE3:QUAT 1567 14.6229 43.9196 -42.356 -0.0432696 -0.538579 -0.50149 -0.675699 +VERTEX_SE3:QUAT 1568 13.9784 47.8536 -46.6319 -0.00550772 -0.58024 -0.492526 -0.648621 +VERTEX_SE3:QUAT 1569 12.9225 51.3014 -51.2182 0.0527547 -0.612069 -0.455359 -0.644388 +VERTEX_SE3:QUAT 1570 11.7845 53.7932 -56.4133 0.0974629 -0.647867 -0.440941 -0.613467 +VERTEX_SE3:QUAT 1571 10.2899 55.8279 -61.6886 0.141884 -0.677605 -0.409168 -0.594392 +VERTEX_SE3:QUAT 1572 8.54964 57.0584 -67.1716 0.19529 -0.700169 -0.385383 -0.568423 +VERTEX_SE3:QUAT 1573 6.78972 57.7495 -72.7758 0.239187 -0.727977 -0.352182 -0.537408 +VERTEX_SE3:QUAT 1574 5.05779 57.4876 -78.4379 0.290026 -0.746676 -0.310076 -0.512068 +VERTEX_SE3:QUAT 1575 3.38908 56.2218 -83.7667 0.325098 -0.771827 -0.28117 -0.468549 +VERTEX_SE3:QUAT 1576 1.47223 54.381 -88.8536 0.337764 -0.799194 -0.258693 -0.424596 +VERTEX_SE3:QUAT 1577 -0.899683 52.1456 -93.6358 0.369494 -0.814676 -0.229881 -0.383318 +VERTEX_SE3:QUAT 1578 -3.53612 49.2712 -98.1631 0.404023 -0.828837 -0.195639 -0.333946 +VERTEX_SE3:QUAT 1579 -6.04094 45.8203 -101.946 0.423563 -0.841729 -0.171443 -0.287567 +VERTEX_SE3:QUAT 1580 -8.87669 42.0756 -105.18 0.459205 -0.841563 -0.139421 -0.24792 +VERTEX_SE3:QUAT 1581 -11.4896 37.7225 -108.266 0.47731 -0.849156 -0.101125 -0.202197 +VERTEX_SE3:QUAT 1582 -13.9975 33.2665 -110.448 0.49054 -0.855236 -0.0679717 -0.152712 +VERTEX_SE3:QUAT 1583 -16.629 28.4522 -111.958 0.524388 -0.84412 -0.0355121 -0.105908 +VERTEX_SE3:QUAT 1584 -18.8718 23.1376 -112.808 0.54146 -0.838185 -0.00594036 -0.0650549 +VERTEX_SE3:QUAT 1585 -21.1319 17.8282 -113.165 0.578609 -0.815002 0.0255155 -0.0182213 +VERTEX_SE3:QUAT 1586 -23.015 12.4436 -112.737 0.605174 -0.792989 0.0608091 0.0351499 +VERTEX_SE3:QUAT 1587 -24.493 6.76724 -111.759 0.621097 -0.773077 0.0936788 0.0883957 +VERTEX_SE3:QUAT 1588 -25.4469 1.32861 -109.795 0.655442 -0.733477 0.1261 0.128476 +VERTEX_SE3:QUAT 1589 -25.7727 -3.90215 -107.507 0.668952 -0.704001 0.164375 0.172818 +VERTEX_SE3:QUAT 1590 -25.7739 -8.87099 -104.735 0.673789 -0.676473 0.202651 0.217545 +VERTEX_SE3:QUAT 1591 -25.3871 -13.1668 -101.553 0.689726 -0.632833 0.233905 0.262848 +VERTEX_SE3:QUAT 1592 -24.5714 -17.2045 -97.4639 0.699831 -0.589577 0.261543 0.30697 +VERTEX_SE3:QUAT 1593 -23.4385 -20.5572 -93.1302 0.685541 -0.565138 0.300662 0.346779 +VERTEX_SE3:QUAT 1594 -22.2109 -23.5403 -88.3939 0.683783 -0.512919 0.336058 0.395499 +VERTEX_SE3:QUAT 1595 -20.6077 -25.6999 -83.2856 0.663069 -0.487555 0.362677 0.437144 +VERTEX_SE3:QUAT 1596 -19.0718 -27.2433 -78.102 0.668106 -0.415402 0.373742 0.491317 +VERTEX_SE3:QUAT 1597 -16.8139 -28.1874 -72.8687 0.658208 -0.371749 0.387616 0.527558 +VERTEX_SE3:QUAT 1598 -14.4095 -28.2477 -67.7285 0.650952 -0.312546 0.407627 0.558943 +VERTEX_SE3:QUAT 1599 -11.556 -27.4863 -62.8195 0.635518 -0.253608 0.420362 0.595899 +VERTEX_SE3:QUAT 1600 -8.62981 -26.1441 -58.2155 0.615242 -0.203413 0.449291 0.61501 +VERTEX_SE3:QUAT 1601 -5.63954 -23.9754 -53.9114 0.590427 -0.161173 0.475057 0.63225 +VERTEX_SE3:QUAT 1602 -2.77771 -21.2967 -49.6103 0.579548 -0.0863407 0.46018 0.667011 +VERTEX_SE3:QUAT 1603 0.400927 -17.8996 -46.2534 0.556774 -0.0270019 0.467091 0.686367 +VERTEX_SE3:QUAT 1604 3.4934 -14.2654 -43.376 0.528198 0.0283709 0.485925 0.695757 +VERTEX_SE3:QUAT 1605 6.32429 -10.1074 -40.8599 0.501469 0.0817899 0.495744 0.704328 +VERTEX_SE3:QUAT 1606 9.06917 -5.40528 -38.9798 0.472945 0.139711 0.497489 0.713659 +VERTEX_SE3:QUAT 1607 11.751 -0.474815 -37.6287 0.445915 0.20478 0.493405 0.718176 +VERTEX_SE3:QUAT 1608 14.1388 4.63307 -37.239 0.419683 0.262786 0.492487 0.715728 +VERTEX_SE3:QUAT 1609 16.1243 10.0178 -37.2529 0.378618 0.315015 0.501079 0.711572 +VERTEX_SE3:QUAT 1610 17.7026 15.4209 -38.1019 0.336898 0.375323 0.476079 0.720404 +VERTEX_SE3:QUAT 1611 19.0239 20.5756 -39.6526 0.320601 0.402801 0.51118 0.688231 +VERTEX_SE3:QUAT 1612 19.6718 25.9471 -41.0226 0.277164 0.454726 0.501048 0.682169 +VERTEX_SE3:QUAT 1613 20.0196 31.112 -43.3184 0.234867 0.510428 0.493433 0.663947 +VERTEX_SE3:QUAT 1614 19.8521 36.1249 -46.1453 0.187023 0.557424 0.478193 0.652405 +VERTEX_SE3:QUAT 1615 19.1634 40.6352 -49.5574 0.156194 0.596522 0.479936 0.624041 +VERTEX_SE3:QUAT 1616 17.9913 44.9652 -53.2279 0.122091 0.634493 0.479767 0.593579 +VERTEX_SE3:QUAT 1617 16.2912 48.7803 -56.9801 0.0726559 0.672647 0.469984 0.566906 +VERTEX_SE3:QUAT 1618 14.1512 51.8009 -61.0682 0.0312339 0.701131 0.466547 0.538306 +VERTEX_SE3:QUAT 1619 11.6319 54.5722 -65.3183 0.00597551 0.730195 0.469213 0.496608 +VERTEX_SE3:QUAT 1620 8.58071 56.829 -69.6264 -0.0488545 0.757854 0.445331 0.474289 +VERTEX_SE3:QUAT 1621 5.4531 58.3343 -73.9792 -0.105113 0.781237 0.408365 0.46028 +VERTEX_SE3:QUAT 1622 2.16001 59.2476 -78.3436 -0.162182 0.800106 0.383933 0.431419 +VERTEX_SE3:QUAT 1623 -0.886564 59.2705 -82.9781 -0.232448 0.813513 0.345598 0.405866 +VERTEX_SE3:QUAT 1624 -3.97913 58.195 -87.6478 -0.282478 0.826557 0.317384 0.369157 +VERTEX_SE3:QUAT 1625 -7.26649 56.3655 -92.0282 -0.297084 0.845032 0.297064 0.33078 +VERTEX_SE3:QUAT 1626 -10.777 54.1141 -95.9147 -0.36703 0.841833 0.252247 0.304923 +VERTEX_SE3:QUAT 1627 -13.5693 51.2805 -99.609 -0.41931 0.840893 0.220151 0.261938 +VERTEX_SE3:QUAT 1628 -16.3351 47.6334 -102.702 -0.482367 0.827014 0.178704 0.226789 +VERTEX_SE3:QUAT 1629 -18.6403 43.5546 -105.336 -0.547827 0.80327 0.129443 0.194649 +VERTEX_SE3:QUAT 1630 -20.2766 38.6745 -107.781 -0.584718 0.791488 0.0887185 0.154212 +VERTEX_SE3:QUAT 1631 -21.5084 33.5899 -109.5 -0.611292 0.781286 0.0597533 0.111104 +VERTEX_SE3:QUAT 1632 -22.641 28.1939 -110.627 -0.628375 0.774478 0.0211687 0.0698539 +VERTEX_SE3:QUAT 1633 -23.5626 22.6697 -111.171 -0.641462 0.766278 -0.0080793 0.0357596 +VERTEX_SE3:QUAT 1634 -24.4542 17.2894 -111.002 -0.674718 0.736527 -0.0476891 -0.0031398 +VERTEX_SE3:QUAT 1635 -24.8136 11.7871 -110.348 -0.672907 0.732188 -0.0929373 -0.0495907 +VERTEX_SE3:QUAT 1636 -24.949 6.32905 -108.869 -0.667731 0.726635 -0.129092 -0.097325 +VERTEX_SE3:QUAT 1637 -25.1335 1.19172 -106.938 -0.674321 0.707304 -0.163901 -0.134718 +VERTEX_SE3:QUAT 1638 -25.2102 -3.84694 -104.331 -0.704969 0.655234 -0.198643 -0.185008 +VERTEX_SE3:QUAT 1639 -24.841 -8.33856 -101.316 -0.703254 0.631782 -0.23338 -0.22764 +VERTEX_SE3:QUAT 1640 -24.1167 -12.5516 -97.6359 -0.711226 0.595477 -0.264599 -0.263728 +VERTEX_SE3:QUAT 1641 -23.0694 -16.4007 -93.4696 -0.709079 0.564324 -0.301009 -0.296883 +VERTEX_SE3:QUAT 1642 -21.8944 -19.5575 -89.1911 -0.712176 0.521292 -0.330357 -0.33455 +VERTEX_SE3:QUAT 1643 -20.4189 -21.8578 -84.4602 -0.722204 0.458897 -0.348766 -0.382358 +VERTEX_SE3:QUAT 1644 -18.535 -23.5817 -79.6472 -0.715385 0.413651 -0.377457 -0.417904 +VERTEX_SE3:QUAT 1645 -16.3039 -24.8942 -74.6271 -0.712085 0.3607 -0.394777 -0.454951 +VERTEX_SE3:QUAT 1646 -13.7617 -25.2923 -69.6979 -0.688327 0.340642 -0.439291 -0.466039 +VERTEX_SE3:QUAT 1647 -11.6166 -25.4064 -64.6686 -0.674484 0.282408 -0.455758 -0.507544 +VERTEX_SE3:QUAT 1648 -9.27987 -24.5745 -59.5982 -0.658818 0.233421 -0.476975 -0.532886 +VERTEX_SE3:QUAT 1649 -6.77542 -23.1419 -54.8736 -0.638455 0.182937 -0.502701 -0.553355 +VERTEX_SE3:QUAT 1650 -4.33082 -20.9584 -50.3848 -0.609773 0.127846 -0.52027 -0.584081 +VERTEX_SE3:QUAT 1651 -1.87995 -18.3011 -46.2043 -0.581298 0.0633406 -0.52966 -0.614444 +VERTEX_SE3:QUAT 1652 0.346239 -14.8843 -42.8265 -0.549576 0.0188224 -0.549904 -0.628663 +VERTEX_SE3:QUAT 1653 2.5808 -11.0215 -39.5784 -0.519022 -0.027552 -0.552796 -0.651363 +VERTEX_SE3:QUAT 1654 4.59741 -6.64227 -37.1207 -0.491391 -0.0882073 -0.552228 -0.667681 +VERTEX_SE3:QUAT 1655 6.58914 -1.9104 -35.0282 -0.461145 -0.147739 -0.552817 -0.678168 +VERTEX_SE3:QUAT 1656 8.36686 3.09238 -33.6455 -0.420801 -0.200749 -0.549962 -0.692942 +VERTEX_SE3:QUAT 1657 10.0935 8.33707 -32.9331 -0.38108 -0.241189 -0.581467 -0.677128 +VERTEX_SE3:QUAT 1658 11.1096 13.7976 -32.6915 -0.346476 -0.292834 -0.574335 -0.681426 +VERTEX_SE3:QUAT 1659 11.9129 19.307 -32.9942 -0.299692 -0.340985 -0.573634 -0.681805 +VERTEX_SE3:QUAT 1660 12.3966 24.5853 -34.3171 -0.263744 -0.38841 -0.576273 -0.668944 +VERTEX_SE3:QUAT 1661 12.5956 30.1464 -35.6504 -0.227385 -0.422025 -0.587035 -0.652366 +VERTEX_SE3:QUAT 1662 12.1397 35.3029 -37.6442 -0.178399 -0.455212 -0.574478 -0.656453 +VERTEX_SE3:QUAT 1663 11.629 40.3383 -40.064 -0.138402 -0.488792 -0.575895 -0.640525 +VERTEX_SE3:QUAT 1664 10.8282 45.1361 -42.928 -0.0829091 -0.526376 -0.549796 -0.643257 +VERTEX_SE3:QUAT 1665 9.79184 49.2643 -46.4162 -0.0494806 -0.553858 -0.5533 -0.620203 +VERTEX_SE3:QUAT 1666 8.39637 53.2175 -50.1416 -0.0109669 -0.583649 -0.538265 -0.607868 +VERTEX_SE3:QUAT 1667 7.02 56.4758 -54.124 0.042397 -0.617127 -0.514032 -0.594246 +VERTEX_SE3:QUAT 1668 5.22624 58.9041 -58.5324 0.104709 -0.647135 -0.470188 -0.590911 +VERTEX_SE3:QUAT 1669 3.68086 60.8728 -63.3482 0.14441 -0.679534 -0.450984 -0.56035 +VERTEX_SE3:QUAT 1670 1.63681 62.1985 -68.261 0.180412 -0.704938 -0.427688 -0.53628 +VERTEX_SE3:QUAT 1671 -0.457689 62.9778 -73.3265 0.211352 -0.726244 -0.415718 -0.505053 +VERTEX_SE3:QUAT 1672 -2.43245 63.356 -78.3269 0.244307 -0.749232 -0.402584 -0.465717 +VERTEX_SE3:QUAT 1673 -4.88814 63.0619 -83.1962 0.270214 -0.768624 -0.385946 -0.432721 +VERTEX_SE3:QUAT 1674 -7.34986 62.1039 -88.0183 0.29924 -0.791357 -0.361284 -0.392024 +VERTEX_SE3:QUAT 1675 -10.0699 60.7172 -92.5946 0.345761 -0.800351 -0.336419 -0.355963 +VERTEX_SE3:QUAT 1676 -12.5296 58.808 -96.7577 0.369288 -0.81938 -0.310162 -0.309908 +VERTEX_SE3:QUAT 1677 -15.1111 56.2276 -100.551 0.411632 -0.823597 -0.282529 -0.269117 +VERTEX_SE3:QUAT 1678 -17.5114 52.9387 -104.101 0.451706 -0.825735 -0.252837 -0.224046 +VERTEX_SE3:QUAT 1679 -19.8515 49.1506 -107.02 0.47887 -0.828616 -0.228582 -0.178408 +VERTEX_SE3:QUAT 1680 -22.2726 45.1834 -109.594 0.541118 -0.807751 -0.182889 -0.145881 +VERTEX_SE3:QUAT 1681 -24.1031 40.5198 -111.732 0.575934 -0.797017 -0.149635 -0.103311 +VERTEX_SE3:QUAT 1682 -25.5217 35.5636 -113.373 0.619112 -0.774167 -0.116947 -0.0607387 +VERTEX_SE3:QUAT 1683 -26.6548 30.2473 -114.326 0.649248 -0.755523 -0.0842662 -0.0236944 +VERTEX_SE3:QUAT 1684 -27.2665 24.9213 -114.988 0.666003 -0.744117 -0.044691 0.027079 +VERTEX_SE3:QUAT 1685 -27.5632 19.438 -114.858 0.67205 -0.736865 -0.00874973 0.0728135 +VERTEX_SE3:QUAT 1686 -27.7476 14.0646 -114.196 0.701038 -0.704147 0.0278386 0.109308 +VERTEX_SE3:QUAT 1687 -27.2852 8.7852 -112.889 0.724879 -0.669558 0.0605917 0.15024 +VERTEX_SE3:QUAT 1688 -26.4509 3.90769 -110.883 0.738123 -0.640413 0.0977683 0.188379 +VERTEX_SE3:QUAT 1689 -25.4874 -0.939574 -108.676 0.756394 -0.600634 0.128723 0.224802 +VERTEX_SE3:QUAT 1690 -24.0397 -5.40563 -105.926 0.749135 -0.586192 0.168635 0.258338 +VERTEX_SE3:QUAT 1691 -22.2975 -9.18573 -102.593 0.788639 -0.500721 0.188947 0.302699 +VERTEX_SE3:QUAT 1692 -19.8183 -12.5728 -99.2867 0.79153 -0.457553 0.222527 0.338537 +VERTEX_SE3:QUAT 1693 -17.1387 -15.3374 -95.5688 0.802676 -0.397353 0.248558 0.368837 +VERTEX_SE3:QUAT 1694 -14.0635 -17.5509 -91.7219 0.803088 -0.346381 0.281271 0.394914 +VERTEX_SE3:QUAT 1695 -10.7878 -18.9123 -87.87 0.776555 -0.340147 0.334618 0.411452 +VERTEX_SE3:QUAT 1696 -7.88459 -19.8143 -83.5482 0.775096 -0.278523 0.359472 0.43867 +VERTEX_SE3:QUAT 1697 -4.68693 -19.9871 -79.3662 0.753701 -0.257915 0.397886 0.455084 +VERTEX_SE3:QUAT 1698 -1.78125 -19.9012 -74.9078 0.729093 -0.229717 0.440514 0.470744 +VERTEX_SE3:QUAT 1699 1.10583 -19.1343 -70.3924 0.703031 -0.202272 0.479732 0.484449 +VERTEX_SE3:QUAT 1700 3.65833 -18.0118 -65.8678 0.676631 -0.162293 0.509101 0.506604 +VERTEX_SE3:QUAT 1701 5.95371 -16.1222 -61.432 0.651282 -0.117588 0.533047 0.52713 +VERTEX_SE3:QUAT 1702 8.01981 -13.5448 -57.1693 0.626652 -0.064713 0.55272 0.545546 +VERTEX_SE3:QUAT 1703 10.0321 -10.3672 -53.3025 0.593798 -0.0290368 0.585487 0.55115 +VERTEX_SE3:QUAT 1704 11.784 -7.02137 -49.7012 0.564886 0.0328262 0.577235 0.588749 +VERTEX_SE3:QUAT 1705 13.4185 -2.90993 -46.7479 0.530033 0.0798813 0.58634 0.607363 +VERTEX_SE3:QUAT 1706 14.9074 1.54308 -44.161 0.496442 0.128986 0.608768 0.605235 +VERTEX_SE3:QUAT 1707 15.9849 6.37149 -42.1041 0.461017 0.18571 0.606217 0.620867 +VERTEX_SE3:QUAT 1708 16.7757 11.3073 -40.7798 0.418347 0.234436 0.602224 0.638241 +VERTEX_SE3:QUAT 1709 17.7254 16.5764 -40.1591 0.371737 0.273433 0.613393 0.640933 +VERTEX_SE3:QUAT 1710 18.2386 21.7656 -39.8814 0.331756 0.318753 0.61069 0.64451 +VERTEX_SE3:QUAT 1711 18.3538 27.1163 -40.2582 0.273838 0.372439 0.584569 0.666769 +VERTEX_SE3:QUAT 1712 18.6439 32.27 -41.5855 0.214422 0.415113 0.552671 0.690115 +VERTEX_SE3:QUAT 1713 18.8494 36.988 -43.522 0.168694 0.461445 0.539828 0.683518 +VERTEX_SE3:QUAT 1714 18.8028 41.4728 -46.2432 0.119608 0.500645 0.520411 0.681338 +VERTEX_SE3:QUAT 1715 18.3999 45.7284 -49.4757 0.0823461 0.535893 0.52167 0.658709 +VERTEX_SE3:QUAT 1716 17.6947 49.5072 -53.027 0.0477729 0.568953 0.50371 0.648295 +VERTEX_SE3:QUAT 1717 16.7633 53.1509 -57.0073 -0.0141507 0.609152 0.465308 0.642045 +VERTEX_SE3:QUAT 1718 15.7382 55.8381 -61.2629 -0.0644207 0.637957 0.434809 0.632299 +VERTEX_SE3:QUAT 1719 14.7778 57.8799 -65.9126 -0.109596 0.671807 0.411745 0.605913 +VERTEX_SE3:QUAT 1720 13.6436 59.3863 -70.6644 -0.155694 0.696145 0.395889 0.578284 +VERTEX_SE3:QUAT 1721 12.1778 60.1726 -75.5037 -0.193207 0.726862 0.377725 0.540062 +VERTEX_SE3:QUAT 1722 10.4588 60.454 -80.4588 -0.237168 0.750106 0.348235 0.50973 +VERTEX_SE3:QUAT 1723 8.47408 60.1856 -85.2879 -0.282727 0.764325 0.320953 0.482558 +VERTEX_SE3:QUAT 1724 6.58503 59.0876 -90.2063 -0.327942 0.774558 0.284178 0.46017 +VERTEX_SE3:QUAT 1725 4.71512 57.623 -95.0331 -0.371741 0.78745 0.247874 0.424606 +VERTEX_SE3:QUAT 1726 2.88702 55.237 -99.3418 -0.416488 0.79547 0.207678 0.388117 +VERTEX_SE3:QUAT 1727 1.10943 52.233 -103.325 -0.446259 0.802552 0.187881 0.348518 +VERTEX_SE3:QUAT 1728 -0.777998 48.8798 -106.918 -0.472369 0.809375 0.154857 0.312729 +VERTEX_SE3:QUAT 1729 -2.57835 45.0413 -110.306 -0.516319 0.80274 0.109197 0.277666 +VERTEX_SE3:QUAT 1730 -4.25142 40.7374 -113.089 -0.541777 0.802679 0.0761444 0.237457 +VERTEX_SE3:QUAT 1731 -5.60147 36.107 -115.278 -0.571319 0.798538 0.0447609 0.184197 +VERTEX_SE3:QUAT 1732 -6.93 31.3453 -116.918 -0.593204 0.791512 0.0178095 0.14595 +VERTEX_SE3:QUAT 1733 -8.22618 26.2631 -118.053 -0.60812 0.787559 -0.0119336 0.0989915 +VERTEX_SE3:QUAT 1734 -9.30245 21.3825 -118.464 -0.634287 0.768151 -0.0546152 0.0681232 +VERTEX_SE3:QUAT 1735 -9.95252 16.242 -118.209 -0.665284 0.741294 -0.0849319 0.0258111 +VERTEX_SE3:QUAT 1736 -10.2369 11.1459 -117.505 -0.70212 0.701573 -0.118365 -0.0285201 +VERTEX_SE3:QUAT 1737 -9.99028 5.98542 -116.054 -0.737138 0.656236 -0.145487 -0.0693911 +VERTEX_SE3:QUAT 1738 -9.37668 1.20296 -114.246 -0.756582 0.619971 -0.180382 -0.103358 +VERTEX_SE3:QUAT 1739 -8.37432 -3.29302 -111.627 -0.771943 0.582017 -0.21456 -0.139011 +VERTEX_SE3:QUAT 1740 -6.99916 -7.42413 -108.92 -0.785772 0.541018 -0.244806 -0.173008 +VERTEX_SE3:QUAT 1741 -5.29755 -11.1107 -105.822 -0.789059 0.504678 -0.276507 -0.21501 +VERTEX_SE3:QUAT 1742 -3.34197 -14.2701 -102.225 -0.786352 0.469051 -0.309345 -0.2568 +VERTEX_SE3:QUAT 1743 -1.29094 -16.9253 -98.4323 -0.781562 0.434547 -0.342965 -0.287586 +VERTEX_SE3:QUAT 1744 0.886144 -19.0216 -94.2001 -0.775893 0.397578 -0.370386 -0.320525 +VERTEX_SE3:QUAT 1745 3.10539 -20.6873 -89.9289 -0.753455 0.382055 -0.406969 -0.347442 +VERTEX_SE3:QUAT 1746 5.10327 -22.0101 -85.4652 -0.73875 0.350029 -0.436545 -0.375708 +VERTEX_SE3:QUAT 1747 7.21298 -22.571 -80.7898 -0.719895 0.321577 -0.468035 -0.399103 +VERTEX_SE3:QUAT 1748 9.15224 -22.8312 -76.0718 -0.704218 0.282876 -0.493661 -0.424684 +VERTEX_SE3:QUAT 1749 11.2164 -22.5221 -71.3073 -0.695364 0.220205 -0.500267 -0.466596 +VERTEX_SE3:QUAT 1750 13.0764 -21.4137 -66.8294 -0.679675 0.156564 -0.515296 -0.497996 +VERTEX_SE3:QUAT 1751 15.2413 -19.6192 -62.5247 -0.649708 0.125159 -0.540286 -0.519909 +VERTEX_SE3:QUAT 1752 17.1693 -17.5208 -58.3435 -0.621282 0.0684227 -0.546802 -0.557078 +VERTEX_SE3:QUAT 1753 19.1797 -14.5706 -54.5745 -0.594585 0.0159177 -0.557294 -0.579344 +VERTEX_SE3:QUAT 1754 21.1514 -11.0028 -51.3791 -0.571614 -0.0341775 -0.56061 -0.598169 +VERTEX_SE3:QUAT 1755 22.9656 -7.34672 -48.5779 -0.546644 -0.0924271 -0.560486 -0.615218 +VERTEX_SE3:QUAT 1756 24.7716 -3.16985 -46.4 -0.51716 -0.1239 -0.583023 -0.614231 +VERTEX_SE3:QUAT 1757 26.1997 1.26538 -44.457 -0.487867 -0.176574 -0.568821 -0.638162 +VERTEX_SE3:QUAT 1758 27.4659 5.84855 -43.1431 -0.449981 -0.224816 -0.587768 -0.633643 +VERTEX_SE3:QUAT 1759 28.3906 10.7262 -42.2917 -0.410668 -0.284947 -0.574244 -0.648384 +VERTEX_SE3:QUAT 1760 29.1479 15.7612 -41.9611 -0.370838 -0.320012 -0.570081 -0.659605 +VERTEX_SE3:QUAT 1761 29.9435 20.8123 -42.3644 -0.32117 -0.360649 -0.561397 -0.672023 +VERTEX_SE3:QUAT 1762 30.416 25.872 -43.3305 -0.264594 -0.415776 -0.543134 -0.679798 +VERTEX_SE3:QUAT 1763 30.6622 30.7378 -45.1362 -0.205979 -0.468736 -0.501144 -0.697649 +VERTEX_SE3:QUAT 1764 30.9132 35.1207 -47.6265 -0.16604 -0.510189 -0.481001 -0.69338 +VERTEX_SE3:QUAT 1765 30.9293 39.2346 -50.6941 -0.12336 -0.552251 -0.472419 -0.675738 +VERTEX_SE3:QUAT 1766 30.5696 43.1203 -54.2478 -0.0762234 -0.590258 -0.45471 -0.662589 +VERTEX_SE3:QUAT 1767 29.8914 46.4357 -58.0933 -0.0273116 -0.626383 -0.428746 -0.650442 +VERTEX_SE3:QUAT 1768 28.9704 49.2093 -62.3129 0.0199179 -0.650667 -0.409659 -0.639073 +VERTEX_SE3:QUAT 1769 27.9897 51.3096 -66.7984 0.0712608 -0.680212 -0.388619 -0.61742 +VERTEX_SE3:QUAT 1770 26.6472 53.058 -71.4007 0.13156 -0.701548 -0.356475 -0.602866 +VERTEX_SE3:QUAT 1771 25.4442 53.9756 -76.2977 0.153664 -0.730742 -0.34002 -0.571656 +VERTEX_SE3:QUAT 1772 23.8981 54.4337 -81.2327 0.196908 -0.751995 -0.31343 -0.545429 +VERTEX_SE3:QUAT 1773 22.2063 54.3459 -86.069 0.227198 -0.777421 -0.288248 -0.510793 +VERTEX_SE3:QUAT 1774 20.3396 53.7692 -90.6246 0.264203 -0.791606 -0.269631 -0.480475 +VERTEX_SE3:QUAT 1775 18.4283 52.782 -95.2096 0.312954 -0.802119 -0.236125 -0.450456 +VERTEX_SE3:QUAT 1776 16.555 51.0196 -99.6263 0.350405 -0.814085 -0.20664 -0.414466 +VERTEX_SE3:QUAT 1777 14.4635 48.7332 -103.544 0.390981 -0.819869 -0.166247 -0.38381 +VERTEX_SE3:QUAT 1778 12.514 45.957 -107.317 0.430203 -0.825026 -0.128333 -0.343204 +VERTEX_SE3:QUAT 1779 10.5568 42.4022 -110.582 0.471437 -0.823381 -0.0870562 -0.303664 +VERTEX_SE3:QUAT 1780 8.933 38.543 -113.344 0.51201 -0.815389 -0.0487322 -0.265728 +VERTEX_SE3:QUAT 1781 7.60768 34.1903 -115.557 0.526133 -0.819297 -0.0132838 -0.227507 +VERTEX_SE3:QUAT 1782 6.11586 29.7697 -117.173 0.564806 -0.801393 0.0214044 -0.195717 +VERTEX_SE3:QUAT 1783 5.01401 25.227 -118.406 0.566565 -0.806042 0.0550131 -0.162093 +VERTEX_SE3:QUAT 1784 3.59872 20.4026 -119.043 0.600955 -0.785017 0.0922103 -0.118739 +VERTEX_SE3:QUAT 1785 2.45655 15.6311 -119.075 0.599136 -0.786874 0.131019 -0.0685542 +VERTEX_SE3:QUAT 1786 1.14532 10.7845 -118.587 0.622752 -0.763225 0.169822 -0.0287804 +VERTEX_SE3:QUAT 1787 0.413051 5.92181 -117.439 0.623257 -0.758587 0.189633 0.0116831 +VERTEX_SE3:QUAT 1788 -0.550402 1.44801 -115.838 0.638944 -0.735351 0.218659 0.0565564 +VERTEX_SE3:QUAT 1789 -1.27553 -2.94234 -113.745 0.648599 -0.716465 0.237323 0.0983639 +VERTEX_SE3:QUAT 1790 -1.77612 -7.32632 -111.161 0.664304 -0.683729 0.264549 0.145701 +VERTEX_SE3:QUAT 1791 -1.88058 -11.3091 -108.251 0.683922 -0.643047 0.288052 0.189122 +VERTEX_SE3:QUAT 1792 -1.70303 -14.9078 -104.882 0.685961 -0.616939 0.313759 0.2245 +VERTEX_SE3:QUAT 1793 -1.28293 -18.2961 -101.243 0.710638 -0.553479 0.336038 0.275197 +VERTEX_SE3:QUAT 1794 -0.333819 -20.976 -97.1635 0.702861 -0.521974 0.364941 0.316775 +VERTEX_SE3:QUAT 1795 0.9475 -23.1931 -92.957 0.708055 -0.463071 0.390961 0.362454 +VERTEX_SE3:QUAT 1796 2.32958 -24.9129 -88.48 0.709762 -0.411282 0.409593 0.399148 +VERTEX_SE3:QUAT 1797 3.86765 -26.0344 -84.1233 0.704619 -0.36351 0.430278 0.431548 +VERTEX_SE3:QUAT 1798 5.72474 -26.5615 -79.587 0.707938 -0.296574 0.441314 0.464876 +VERTEX_SE3:QUAT 1799 8.06405 -26.259 -75.2662 0.706803 -0.222294 0.444765 0.503188 +VERTEX_SE3:QUAT 1800 10.5831 -25.3833 -71.2905 0.692567 -0.173663 0.457029 0.530393 +VERTEX_SE3:QUAT 1801 13.3092 -23.7607 -67.2852 0.663459 -0.153994 0.495432 0.539125 +VERTEX_SE3:QUAT 1802 15.6528 -21.8473 -63.3233 0.65275 -0.0626241 0.473098 0.588366 +VERTEX_SE3:QUAT 1803 18.4855 -19.5302 -60.2406 0.626986 -0.0297378 0.492943 0.602505 +VERTEX_SE3:QUAT 1804 20.8898 -16.4764 -57.3705 0.603131 0.0250586 0.48651 0.631596 +VERTEX_SE3:QUAT 1805 23.412 -13.1248 -54.8504 0.577125 0.0692554 0.500371 0.641684 +VERTEX_SE3:QUAT 1806 25.7452 -9.38816 -52.6246 0.543109 0.115471 0.5186 0.650194 +VERTEX_SE3:QUAT 1807 27.87 -5.3991 -51.032 0.51465 0.17012 0.515881 0.663371 +VERTEX_SE3:QUAT 1808 29.8888 -1.1351 -49.8299 0.474368 0.234203 0.490148 0.692733 +VERTEX_SE3:QUAT 1809 31.7845 3.28978 -49.3927 0.439638 0.274113 0.497456 0.695786 +VERTEX_SE3:QUAT 1810 33.553 7.92064 -49.3473 0.396214 0.325846 0.485536 0.70788 +VERTEX_SE3:QUAT 1811 35.1059 12.4174 -50.058 0.356537 0.381123 0.471791 0.710662 +VERTEX_SE3:QUAT 1812 36.0944 17.0727 -51.3571 0.326272 0.411275 0.490248 0.695741 +VERTEX_SE3:QUAT 1813 36.8208 21.5777 -52.9338 0.288957 0.454607 0.482437 0.690718 +VERTEX_SE3:QUAT 1814 37.3836 26.0833 -55.1118 0.250176 0.502842 0.468081 0.682248 +VERTEX_SE3:QUAT 1815 37.4594 30.3295 -57.5187 0.211895 0.536659 0.478114 0.662197 +VERTEX_SE3:QUAT 1816 37.2815 34.3701 -60.2781 0.167255 0.574424 0.4616 0.654971 +VERTEX_SE3:QUAT 1817 36.7281 38.0438 -63.2516 0.107757 0.615496 0.415101 0.661245 +VERTEX_SE3:QUAT 1818 36.12 40.9874 -66.8971 0.0698278 0.652747 0.383276 0.649727 +VERTEX_SE3:QUAT 1819 35.1286 43.4657 -70.9501 0.0175837 0.684839 0.343525 0.642399 +VERTEX_SE3:QUAT 1820 34.2852 45.5599 -75.2333 -0.0348392 0.716633 0.312338 0.62263 +VERTEX_SE3:QUAT 1821 33.1306 46.751 -79.9577 -0.0846234 0.736543 0.275378 0.611973 +VERTEX_SE3:QUAT 1822 31.7165 47.2742 -84.6133 -0.10805 0.767051 0.249189 0.581259 +VERTEX_SE3:QUAT 1823 30.1016 47.5083 -89.1866 -0.163978 0.787861 0.206033 0.556719 +VERTEX_SE3:QUAT 1824 28.5712 46.9178 -93.7032 -0.243348 0.80078 0.149589 0.526457 +VERTEX_SE3:QUAT 1825 26.9808 45.3754 -98.0029 -0.27675 0.820152 0.125284 0.484834 +VERTEX_SE3:QUAT 1826 25.2216 43.5184 -102.093 -0.314947 0.831069 0.0929824 0.448873 +VERTEX_SE3:QUAT 1827 23.2777 40.9466 -105.808 -0.347133 0.839686 0.0637036 0.412757 +VERTEX_SE3:QUAT 1828 21.3584 38.1583 -109.163 -0.396557 0.836565 0.0256783 0.377151 +VERTEX_SE3:QUAT 1829 19.4787 34.8068 -111.954 -0.464421 0.815605 -0.0250174 0.344203 +VERTEX_SE3:QUAT 1830 17.8438 30.8681 -114.434 -0.476014 0.826416 -0.0570404 0.295287 +VERTEX_SE3:QUAT 1831 16.3724 26.8087 -116.166 -0.498861 0.823655 -0.0890972 0.254543 +VERTEX_SE3:QUAT 1832 14.5742 22.5867 -117.428 -0.525567 0.813728 -0.129876 0.211562 +VERTEX_SE3:QUAT 1833 13.0301 18.0247 -118.139 -0.553903 0.798802 -0.165969 0.166014 +VERTEX_SE3:QUAT 1834 11.7527 13.6369 -118.142 -0.557475 0.799218 -0.18891 0.121595 +VERTEX_SE3:QUAT 1835 10.2025 9.26884 -117.502 -0.563942 0.793079 -0.216599 0.0779735 +VERTEX_SE3:QUAT 1836 8.55616 4.6771 -116.574 -0.566834 0.786776 -0.24179 0.0349337 +VERTEX_SE3:QUAT 1837 6.90691 0.467435 -115.252 -0.590051 0.760767 -0.269676 -0.0186716 +VERTEX_SE3:QUAT 1838 5.63968 -3.60048 -113.428 -0.586862 0.750033 -0.297683 -0.0665471 +VERTEX_SE3:QUAT 1839 4.22005 -7.46019 -110.979 -0.60522 0.72006 -0.318105 -0.118458 +VERTEX_SE3:QUAT 1840 3.34711 -11.0246 -108.155 -0.633467 0.675147 -0.338914 -0.16743 +VERTEX_SE3:QUAT 1841 2.90829 -14.2741 -104.794 -0.642194 0.634792 -0.368241 -0.221413 +VERTEX_SE3:QUAT 1842 2.67608 -17.0609 -101.112 -0.64256 0.598015 -0.392463 -0.274713 +VERTEX_SE3:QUAT 1843 2.89894 -19.4675 -96.9835 -0.647382 0.560343 -0.411738 -0.312064 +VERTEX_SE3:QUAT 1844 3.37749 -21.4837 -92.6863 -0.659031 0.50567 -0.423024 -0.361977 +VERTEX_SE3:QUAT 1845 4.20604 -22.9738 -88.3095 -0.686822 0.414553 -0.416412 -0.42781 +VERTEX_SE3:QUAT 1846 5.68258 -23.6794 -83.8709 -0.676651 0.372966 -0.439231 -0.458385 +VERTEX_SE3:QUAT 1847 7.54988 -23.9229 -79.7236 -0.657304 0.346879 -0.464138 -0.481873 +VERTEX_SE3:QUAT 1848 9.1102 -23.6919 -75.3852 -0.647814 0.290096 -0.474393 -0.520704 +VERTEX_SE3:QUAT 1849 10.986 -23.1694 -71.1959 -0.636545 0.237654 -0.48936 -0.546679 +VERTEX_SE3:QUAT 1850 13.0294 -21.9153 -67.0609 -0.620064 0.183716 -0.501406 -0.574771 +VERTEX_SE3:QUAT 1851 15.1863 -20.1117 -63.3682 -0.611641 0.12468 -0.494448 -0.604873 +VERTEX_SE3:QUAT 1852 17.4377 -17.8715 -59.9237 -0.590802 0.0669737 -0.495925 -0.632871 +VERTEX_SE3:QUAT 1853 19.8188 -14.9895 -57.1198 -0.567187 -0.00441288 -0.481316 -0.668292 +VERTEX_SE3:QUAT 1854 22.4721 -11.9406 -54.7249 -0.538903 -0.0327277 -0.504223 -0.673997 +VERTEX_SE3:QUAT 1855 24.816 -8.44905 -52.6779 -0.515762 -0.0691068 -0.5177 -0.679118 +VERTEX_SE3:QUAT 1856 26.8584 -4.8781 -51.0236 -0.482434 -0.122339 -0.50986 -0.701665 +VERTEX_SE3:QUAT 1857 29.0477 -0.831181 -49.9245 -0.448229 -0.158021 -0.537615 -0.696485 +VERTEX_SE3:QUAT 1858 30.7125 3.29662 -49.1273 -0.409743 -0.203336 -0.538436 -0.707709 +VERTEX_SE3:QUAT 1859 32.2059 7.58069 -48.6532 -0.388914 -0.228269 -0.56873 -0.687885 +VERTEX_SE3:QUAT 1860 33.2583 12.1263 -48.4906 -0.348953 -0.274092 -0.570264 -0.691307 +VERTEX_SE3:QUAT 1861 34.2611 16.5893 -48.7969 -0.318018 -0.317254 -0.55901 -0.696938 +VERTEX_SE3:QUAT 1862 35.0353 20.9829 -49.4769 -0.276738 -0.368367 -0.531964 -0.710448 +VERTEX_SE3:QUAT 1863 35.8264 25.3524 -50.8671 -0.232598 -0.410906 -0.511987 -0.717582 +VERTEX_SE3:QUAT 1864 36.5607 29.511 -52.7004 -0.18915 -0.46085 -0.46094 -0.734421 +VERTEX_SE3:QUAT 1865 37.141 33.312 -55.3072 -0.161272 -0.49165 -0.467312 -0.716862 +VERTEX_SE3:QUAT 1866 37.3912 36.7949 -58.0483 -0.11477 -0.533974 -0.443267 -0.710784 +VERTEX_SE3:QUAT 1867 37.3825 39.9593 -61.353 -0.0752394 -0.566665 -0.418105 -0.705987 +VERTEX_SE3:QUAT 1868 37.2092 42.9206 -64.8185 -0.0277072 -0.603711 -0.371908 -0.704592 +VERTEX_SE3:QUAT 1869 37.1136 45.1078 -68.8853 0.00151276 -0.635482 -0.361714 -0.682146 +VERTEX_SE3:QUAT 1870 36.7333 47.2674 -73.1469 0.0472706 -0.665657 -0.324678 -0.670261 +VERTEX_SE3:QUAT 1871 36.1794 48.7662 -77.4331 0.0975691 -0.695203 -0.281402 -0.654207 +VERTEX_SE3:QUAT 1872 35.6201 49.7724 -81.772 0.121573 -0.718951 -0.250529 -0.636839 +VERTEX_SE3:QUAT 1873 34.9018 50.0777 -86.0445 0.1829 -0.74116 -0.20284 -0.613258 +VERTEX_SE3:QUAT 1874 34.2687 49.7826 -90.4951 0.224929 -0.759771 -0.163136 -0.587828 +VERTEX_SE3:QUAT 1875 33.2811 48.8014 -94.8743 0.273226 -0.775536 -0.119504 -0.556426 +VERTEX_SE3:QUAT 1876 32.3267 47.1725 -98.8177 0.315059 -0.78379 -0.0855283 -0.528295 +VERTEX_SE3:QUAT 1877 31.1583 45.0229 -102.66 0.342576 -0.792664 -0.0539923 -0.501409 +VERTEX_SE3:QUAT 1878 29.9437 42.4277 -106.287 0.413416 -0.78209 0.00837118 -0.466211 +VERTEX_SE3:QUAT 1879 28.8991 39.3258 -109.443 0.447004 -0.786305 0.043858 -0.42425 +VERTEX_SE3:QUAT 1880 27.7468 35.6787 -111.911 0.503194 -0.770193 0.103907 -0.377891 +VERTEX_SE3:QUAT 1881 26.7363 31.665 -113.821 0.53413 -0.761369 0.15028 -0.335318 +VERTEX_SE3:QUAT 1882 25.9082 27.5418 -115.024 0.551753 -0.754917 0.187916 -0.300593 +VERTEX_SE3:QUAT 1883 24.808 23.1748 -115.86 0.606764 -0.714431 0.240782 -0.251892 +VERTEX_SE3:QUAT 1884 24.2749 18.7315 -115.804 0.627296 -0.693792 0.287624 -0.205976 +VERTEX_SE3:QUAT 1885 23.7253 14.4106 -115.189 0.648964 -0.665736 0.331228 -0.161027 +VERTEX_SE3:QUAT 1886 23.2233 10.1754 -113.956 0.674505 -0.636583 0.360248 -0.100133 +VERTEX_SE3:QUAT 1887 23.0268 6.06638 -112.095 0.674344 -0.622919 0.391954 -0.0600359 +VERTEX_SE3:QUAT 1888 22.8178 2.27255 -109.605 0.696663 -0.571508 0.433633 0.000501852 +VERTEX_SE3:QUAT 1889 22.8217 -1.02691 -106.54 0.697766 -0.547641 0.459961 0.0405799 +VERTEX_SE3:QUAT 1890 22.597 -4.03812 -103.411 0.69724 -0.512569 0.494293 0.0824868 +VERTEX_SE3:QUAT 1891 22.5395 -6.58875 -99.8748 0.687425 -0.492902 0.519478 0.120982 +VERTEX_SE3:QUAT 1892 22.603 -8.76661 -96.1537 0.698813 -0.431847 0.539393 0.184997 +VERTEX_SE3:QUAT 1893 22.7687 -10.2679 -92.2126 0.689517 -0.407812 0.555674 0.222444 +VERTEX_SE3:QUAT 1894 23.1328 -11.3069 -87.8901 0.670246 -0.391138 0.581248 0.244808 +VERTEX_SE3:QUAT 1895 23.425 -12.0032 -83.5548 0.659 -0.343392 0.604165 0.287724 +VERTEX_SE3:QUAT 1896 23.62 -12.0696 -79.2277 0.644739 -0.302785 0.622664 0.323918 +VERTEX_SE3:QUAT 1897 23.8919 -11.6419 -74.7967 0.627954 -0.265854 0.633973 0.364792 +VERTEX_SE3:QUAT 1898 24.2284 -10.8164 -70.4151 0.624073 -0.208786 0.634265 0.405769 +VERTEX_SE3:QUAT 1899 24.7259 -9.28434 -66.386 0.604605 -0.158976 0.647219 0.436219 +VERTEX_SE3:QUAT 1900 25.0477 -7.34429 -62.6674 0.579375 -0.125204 0.66271 0.457673 +VERTEX_SE3:QUAT 1901 25.3804 -5.27224 -58.8889 0.551791 -0.0883615 0.676969 0.478991 +VERTEX_SE3:QUAT 1902 25.7945 -2.76946 -55.388 0.522386 -0.0510177 0.679143 0.513104 +VERTEX_SE3:QUAT 1903 26.0469 0.247693 -52.1618 0.497108 -0.00495073 0.668835 0.552738 +VERTEX_SE3:QUAT 1904 26.5324 3.46508 -49.4137 0.465878 0.0255424 0.689739 0.553683 +VERTEX_SE3:QUAT 1905 26.7327 7.03706 -47.0865 0.435881 0.0704996 0.69361 0.56916 +VERTEX_SE3:QUAT 1906 26.7936 11.1071 -45.1151 0.391721 0.137093 0.656 0.630416 +VERTEX_SE3:QUAT 1907 27.2816 15.2486 -43.9602 0.355148 0.188834 0.635319 0.659227 +VERTEX_SE3:QUAT 1908 27.8607 19.6675 -43.5303 0.312269 0.23494 0.613622 0.686119 +VERTEX_SE3:QUAT 1909 28.5381 23.8911 -43.5614 0.270285 0.276561 0.596011 0.703727 +VERTEX_SE3:QUAT 1910 29.0937 28.0798 -44.0251 0.237155 0.31518 0.585564 0.708191 +VERTEX_SE3:QUAT 1911 29.6402 32.1604 -45.0252 0.20302 0.354213 0.566476 0.715836 +VERTEX_SE3:QUAT 1912 30.1254 36.2125 -46.3864 0.162054 0.389218 0.532349 0.734066 +VERTEX_SE3:QUAT 1913 30.6861 39.982 -48.4016 0.109529 0.436849 0.47324 0.757107 +VERTEX_SE3:QUAT 1914 31.4397 43.3332 -50.9776 0.0596884 0.476364 0.426596 0.766506 +VERTEX_SE3:QUAT 1915 32.2982 46.1397 -54.0817 0.0216214 0.511537 0.391257 0.76471 +VERTEX_SE3:QUAT 1916 32.8167 48.5025 -57.659 -0.0233504 0.546784 0.351507 0.759555 +VERTEX_SE3:QUAT 1917 33.4954 50.5334 -61.5563 -0.0843276 0.576144 0.279967 0.76326 +VERTEX_SE3:QUAT 1918 34.2298 51.6609 -65.5886 -0.129966 0.588168 0.234116 0.763123 +VERTEX_SE3:QUAT 1919 35.0789 52.2317 -69.6365 -0.153596 0.612376 0.213532 0.745526 +VERTEX_SE3:QUAT 1920 35.6499 52.4845 -73.8401 -0.197 0.626061 0.157956 0.737759 +VERTEX_SE3:QUAT 1921 36.3567 52.1457 -78.0428 -0.235772 0.64664 0.093429 0.719402 +VERTEX_SE3:QUAT 1922 36.9073 51.0145 -82.1668 -0.263384 0.66693 0.0461642 0.695487 +VERTEX_SE3:QUAT 1923 37.2037 49.5174 -86.0709 -0.283508 0.694427 0.0197302 0.661063 +VERTEX_SE3:QUAT 1924 37.2751 47.5824 -89.9069 -0.321589 0.706472 -0.014352 0.630294 +VERTEX_SE3:QUAT 1925 37.0988 45.1089 -93.4494 -0.358345 0.716121 -0.0661239 0.595304 +VERTEX_SE3:QUAT 1926 37.1004 42.3507 -96.8766 -0.401492 0.716707 -0.11727 0.558017 +VERTEX_SE3:QUAT 1927 36.8956 39.1229 -99.5758 -0.421117 0.726162 -0.150768 0.522129 +VERTEX_SE3:QUAT 1928 36.4589 35.6218 -102.058 -0.436206 0.736568 -0.178263 0.485195 +VERTEX_SE3:QUAT 1929 35.8329 31.9945 -104.096 -0.45963 0.740761 -0.211763 0.44178 +VERTEX_SE3:QUAT 1930 34.9371 28.2614 -105.598 -0.475216 0.740234 -0.245979 0.407084 +VERTEX_SE3:QUAT 1931 33.8539 24.2951 -106.725 -0.493505 0.73447 -0.283385 0.36973 +VERTEX_SE3:QUAT 1932 32.9179 20.3514 -107.385 -0.518462 0.724631 -0.315016 0.326913 +VERTEX_SE3:QUAT 1933 31.9253 16.4305 -107.795 -0.536901 0.71779 -0.345746 0.277441 +VERTEX_SE3:QUAT 1934 30.8508 12.4124 -107.72 -0.564487 0.698418 -0.380566 0.220764 +VERTEX_SE3:QUAT 1935 29.8676 8.33339 -106.703 -0.575855 0.683728 -0.410247 0.180568 +VERTEX_SE3:QUAT 1936 28.7149 4.33134 -105.399 -0.590974 0.664821 -0.437262 0.132533 +VERTEX_SE3:QUAT 1937 27.6795 0.708396 -103.675 -0.603412 0.639589 -0.465114 0.102419 +VERTEX_SE3:QUAT 1938 26.7625 -2.87593 -101.631 -0.62691 0.59849 -0.49696 0.0427087 +VERTEX_SE3:QUAT 1939 26.0841 -5.97222 -99.0222 -0.6245 0.587718 -0.514376 -0.00189799 +VERTEX_SE3:QUAT 1940 25.2317 -8.61877 -96.2511 -0.618079 0.576975 -0.533019 -0.0311242 +VERTEX_SE3:QUAT 1941 24.22 -11.3114 -93.09 -0.622477 0.535096 -0.564254 -0.0883863 +VERTEX_SE3:QUAT 1942 23.3555 -13.3856 -89.576 -0.636577 0.486921 -0.580368 -0.144398 +VERTEX_SE3:QUAT 1943 22.8346 -14.9233 -85.7379 -0.630118 0.451356 -0.602648 -0.189854 +VERTEX_SE3:QUAT 1944 22.323 -16.1499 -81.6859 -0.631188 0.409905 -0.612529 -0.241635 +VERTEX_SE3:QUAT 1945 22.2128 -16.7731 -77.6889 -0.628162 0.352647 -0.626124 -0.298366 +VERTEX_SE3:QUAT 1946 22.1915 -16.6369 -73.546 -0.615707 0.310402 -0.638943 -0.341039 +VERTEX_SE3:QUAT 1947 22.2804 -16.1841 -69.5018 -0.592322 0.283422 -0.660708 -0.363719 +VERTEX_SE3:QUAT 1948 22.2105 -15.2488 -65.5532 -0.580436 0.242632 -0.661136 -0.408808 +VERTEX_SE3:QUAT 1949 22.3765 -13.9032 -61.8 -0.554985 0.206144 -0.669035 -0.449319 +VERTEX_SE3:QUAT 1950 22.5351 -11.9277 -58.0689 -0.531549 0.180024 -0.686125 -0.462903 +VERTEX_SE3:QUAT 1951 22.7396 -9.85755 -54.6411 -0.507581 0.150841 -0.695361 -0.485883 +VERTEX_SE3:QUAT 1952 22.9657 -7.31208 -51.3225 -0.495108 0.0870309 -0.677229 -0.537266 +VERTEX_SE3:QUAT 1953 23.2559 -4.54176 -48.3425 -0.465365 0.063185 -0.691047 -0.549452 +VERTEX_SE3:QUAT 1954 23.4926 -1.44037 -45.609 -0.436601 0.0243009 -0.68175 -0.58652 +VERTEX_SE3:QUAT 1955 23.8738 1.84572 -43.3055 -0.412438 -0.0332474 -0.646561 -0.640896 +VERTEX_SE3:QUAT 1956 24.6629 5.44628 -41.6704 -0.382043 -0.0700645 -0.64494 -0.658169 +VERTEX_SE3:QUAT 1957 25.3546 9.14456 -40.2113 -0.357787 -0.0945648 -0.64313 -0.670395 +VERTEX_SE3:QUAT 1958 25.895 13.0559 -39.0014 -0.324971 -0.132496 -0.638677 -0.684785 +VERTEX_SE3:QUAT 1959 26.4451 17.1852 -38.4334 -0.306242 -0.167063 -0.629974 -0.693858 +VERTEX_SE3:QUAT 1960 27.0476 21.1431 -38.0745 -0.275255 -0.211032 -0.594897 -0.725119 +VERTEX_SE3:QUAT 1961 27.9462 25.2051 -38.2216 -0.240418 -0.245484 -0.584132 -0.735341 +VERTEX_SE3:QUAT 1962 28.9563 29.1259 -38.9705 -0.209881 -0.283757 -0.559883 -0.749641 +VERTEX_SE3:QUAT 1963 30.0056 33.1094 -40.0107 -0.165159 -0.326051 -0.535977 -0.761014 +VERTEX_SE3:QUAT 1964 30.8521 36.7006 -41.5295 -0.11607 -0.371437 -0.496016 -0.776228 +VERTEX_SE3:QUAT 1965 31.8559 39.972 -43.686 -0.0736726 -0.403646 -0.470868 -0.780977 +VERTEX_SE3:QUAT 1966 32.7363 43.1188 -46.0977 -0.0293434 -0.438003 -0.44219 -0.782151 +VERTEX_SE3:QUAT 1967 33.7094 45.7912 -49.0387 -0.00157163 -0.470381 -0.415714 -0.778409 +VERTEX_SE3:QUAT 1968 34.4338 48.148 -52.2724 0.0342449 -0.501432 -0.387521 -0.7728 +VERTEX_SE3:QUAT 1969 35.3083 50.2396 -55.5436 0.0673008 -0.533018 -0.356374 -0.764435 +VERTEX_SE3:QUAT 1970 36.0411 51.8766 -58.9647 0.0962395 -0.561066 -0.343371 -0.74702 +VERTEX_SE3:QUAT 1971 36.6131 53.2737 -62.6055 0.135119 -0.584789 -0.304566 -0.739597 +VERTEX_SE3:QUAT 1972 37.1484 54.1478 -66.3544 0.156961 -0.605541 -0.285189 -0.726189 +VERTEX_SE3:QUAT 1973 37.715 54.7126 -70.2218 0.185888 -0.62846 -0.254064 -0.711291 +VERTEX_SE3:QUAT 1974 38.1247 54.8891 -74.2941 0.217083 -0.648576 -0.210935 -0.698377 +VERTEX_SE3:QUAT 1975 38.3314 54.6456 -78.2621 0.258231 -0.665956 -0.172964 -0.678162 +VERTEX_SE3:QUAT 1976 38.4661 54.0053 -82.1689 0.274454 -0.686541 -0.144986 -0.657507 +VERTEX_SE3:QUAT 1977 38.3398 53.0188 -85.9922 0.308981 -0.697687 -0.102229 -0.63821 +VERTEX_SE3:QUAT 1978 38.4802 51.5015 -89.6035 0.325815 -0.715355 -0.0835073 -0.612485 +VERTEX_SE3:QUAT 1979 38.3481 49.681 -93.3065 0.354228 -0.729605 -0.0474233 -0.583053 +VERTEX_SE3:QUAT 1980 38.0906 47.6382 -96.553 0.441396 -0.705482 0.0463846 -0.552551 +VERTEX_SE3:QUAT 1981 38.0377 44.7343 -99.164 0.471502 -0.706713 0.0891173 -0.519904 +VERTEX_SE3:QUAT 1982 38.0172 41.5875 -101.522 0.505517 -0.697207 0.136841 -0.48952 +VERTEX_SE3:QUAT 1983 38.0405 38.0754 -103.271 0.550128 -0.676354 0.187267 -0.452589 +VERTEX_SE3:QUAT 1984 38.0799 34.4989 -104.411 0.590092 -0.652045 0.244535 -0.408451 +VERTEX_SE3:QUAT 1985 38.0679 30.6487 -105.06 0.625272 -0.622606 0.29801 -0.364125 +VERTEX_SE3:QUAT 1986 38.2808 26.7962 -104.897 0.632131 -0.620769 0.326691 -0.329133 +VERTEX_SE3:QUAT 1987 38.3137 22.7309 -104.526 0.636596 -0.607446 0.375663 -0.290915 +VERTEX_SE3:QUAT 1988 38.157 18.8547 -103.784 0.65951 -0.573015 0.426247 -0.234549 +VERTEX_SE3:QUAT 1989 38.1115 15.1407 -102.285 0.640776 -0.584583 0.453026 -0.206002 +VERTEX_SE3:QUAT 1990 37.8168 11.7383 -100.808 0.626514 -0.593839 0.469054 -0.186611 +VERTEX_SE3:QUAT 1991 37.2569 8.21401 -99.1442 0.626214 -0.581313 0.496742 -0.152245 +VERTEX_SE3:QUAT 1992 36.544 4.95059 -97.0537 0.631316 -0.560694 0.525229 -0.105813 +VERTEX_SE3:QUAT 1993 35.9379 2.02926 -94.5768 0.649364 -0.512555 0.560502 -0.0380824 +VERTEX_SE3:QUAT 1994 35.3966 -0.531115 -91.7658 0.659274 -0.470718 0.586057 0.0178509 +VERTEX_SE3:QUAT 1995 34.8155 -2.67465 -88.619 0.675929 -0.407144 0.606971 0.0945497 +VERTEX_SE3:QUAT 1996 34.6742 -4.12985 -85.0992 0.670366 -0.378963 0.621549 0.143784 +VERTEX_SE3:QUAT 1997 34.6212 -5.18801 -81.1638 0.65831 -0.346652 0.643421 0.180194 +VERTEX_SE3:QUAT 1998 34.4936 -5.75475 -77.6143 0.648733 -0.307492 0.65958 0.222596 +VERTEX_SE3:QUAT 1999 34.3039 -5.99817 -73.8715 0.634941 -0.267576 0.677363 0.257745 +VERTEX_SE3:QUAT 2000 34.1035 -5.60454 -70.1743 0.620065 -0.237372 0.688172 0.292562 +VERTEX_SE3:QUAT 2001 33.9906 -4.79051 -66.2956 0.615535 -0.194396 0.688358 0.330894 +VERTEX_SE3:QUAT 2002 33.9908 -3.57622 -62.7105 0.593424 -0.167432 0.702848 0.354711 +VERTEX_SE3:QUAT 2003 33.8238 -2.18416 -59.2956 0.573689 -0.114307 0.707189 0.397114 +VERTEX_SE3:QUAT 2004 33.7576 -0.322758 -55.8436 0.557446 -0.0752286 0.71137 0.421363 +VERTEX_SE3:QUAT 2005 33.9103 1.8933 -52.7642 0.522356 -0.0459388 0.72775 0.442056 +VERTEX_SE3:QUAT 2006 33.7838 4.41751 -49.9047 0.493363 -0.0058646 0.730466 0.472206 +VERTEX_SE3:QUAT 2007 33.687 7.33696 -47.5205 0.466215 0.0191175 0.736763 0.489345 +VERTEX_SE3:QUAT 2008 33.4971 10.3456 -45.2825 0.436476 0.0495397 0.736817 0.513942 +VERTEX_SE3:QUAT 2009 33.2458 13.4162 -43.0411 0.400947 0.0902637 0.729365 0.546918 +VERTEX_SE3:QUAT 2010 33.0655 16.7861 -41.6031 0.366186 0.124402 0.718768 0.577759 +VERTEX_SE3:QUAT 2011 32.9125 20.3868 -40.2805 0.337719 0.16647 0.700342 0.606427 +VERTEX_SE3:QUAT 2012 32.8458 24.0828 -39.4982 0.308046 0.189491 0.700298 0.615453 +VERTEX_SE3:QUAT 2013 32.6415 27.7804 -39.1596 0.278683 0.22688 0.685363 0.633355 +VERTEX_SE3:QUAT 2014 32.4924 31.3619 -39.1426 0.246785 0.26401 0.663221 0.655388 +VERTEX_SE3:QUAT 2015 32.6553 35.0545 -39.4478 0.213121 0.306461 0.612899 0.69643 +VERTEX_SE3:QUAT 2016 32.9323 38.6785 -40.4832 0.177037 0.347665 0.57947 0.715543 +VERTEX_SE3:QUAT 2017 33.437 42.0312 -41.9323 0.142337 0.373602 0.553796 0.730391 +VERTEX_SE3:QUAT 2018 33.9936 45.3846 -43.587 0.0999275 0.4113 0.498515 0.756525 +VERTEX_SE3:QUAT 2019 34.8862 48.3497 -45.6364 0.0662424 0.437157 0.466666 0.765982 +VERTEX_SE3:QUAT 2020 35.5547 50.9641 -48.0753 0.0277819 0.467169 0.431425 0.771268 +VERTEX_SE3:QUAT 2021 36.4483 53.2615 -50.8267 -4.33837e-05 0.50005 0.411016 0.762244 +VERTEX_SE3:QUAT 2022 37.0763 55.5941 -53.6323 -0.0475235 0.528917 0.352311 0.770626 +VERTEX_SE3:QUAT 2023 37.8209 57.0657 -56.9752 -0.079073 0.549425 0.328005 0.764391 +VERTEX_SE3:QUAT 2024 38.4013 58.36 -60.2655 -0.113315 0.576843 0.299218 0.751586 +VERTEX_SE3:QUAT 2025 38.9917 59.1132 -63.8023 -0.151278 0.603773 0.257749 0.739012 +VERTEX_SE3:QUAT 2026 39.4056 59.4142 -67.302 -0.205744 0.612908 0.218264 0.731009 +VERTEX_SE3:QUAT 2027 39.9779 59.1909 -70.9834 -0.256847 0.624029 0.150281 0.722519 +VERTEX_SE3:QUAT 2028 40.6396 58.4036 -74.4202 -0.273819 0.643123 0.130724 0.703084 +VERTEX_SE3:QUAT 2029 41.1789 57.5278 -77.7723 -0.303046 0.654731 0.085125 0.6872 +VERTEX_SE3:QUAT 2030 41.6879 56.1767 -81.0432 -0.326457 0.670802 0.0438006 0.664479 +VERTEX_SE3:QUAT 2031 41.9368 54.6261 -84.2859 -0.374687 0.66847 -0.0131126 0.642328 +VERTEX_SE3:QUAT 2032 42.3959 52.3987 -87.2003 -0.421308 0.662327 -0.0640749 0.616212 +VERTEX_SE3:QUAT 2033 42.8953 49.9488 -89.7383 -0.452308 0.660718 -0.11547 0.587823 +VERTEX_SE3:QUAT 2034 43.2142 47.0636 -91.882 -0.475058 0.659802 -0.157207 0.560594 +VERTEX_SE3:QUAT 2035 43.3414 44.0206 -93.832 -0.49815 0.651311 -0.2046 0.534584 +VERTEX_SE3:QUAT 2036 43.5498 40.7284 -95.4504 -0.521598 0.643728 -0.245366 0.503333 +VERTEX_SE3:QUAT 2037 43.6198 37.3641 -96.6868 -0.539966 0.635795 -0.295138 0.465935 +VERTEX_SE3:QUAT 2038 43.7341 33.9081 -97.4164 -0.573304 0.616927 -0.335583 0.422028 +VERTEX_SE3:QUAT 2039 43.6891 30.1796 -97.6114 -0.592195 0.599684 -0.386554 0.374513 +VERTEX_SE3:QUAT 2040 43.5529 26.7501 -97.4033 -0.594516 0.593552 -0.419085 0.344405 +VERTEX_SE3:QUAT 2041 43.327 23.3131 -96.86 -0.613391 0.560717 -0.471611 0.294842 +VERTEX_SE3:QUAT 2042 42.8646 19.8914 -95.6347 -0.63508 0.521111 -0.51728 0.23987 +VERTEX_SE3:QUAT 2043 42.5434 16.8337 -93.9228 -0.635985 0.508994 -0.545784 0.196385 +VERTEX_SE3:QUAT 2044 42.0566 13.8695 -91.9282 -0.640831 0.49096 -0.569683 0.154126 +VERTEX_SE3:QUAT 2045 41.6711 11.1741 -89.6218 -0.636752 0.469875 -0.599854 0.118068 +VERTEX_SE3:QUAT 2046 41.2516 8.55799 -87.2104 -0.639841 0.427379 -0.635546 0.0635068 +VERTEX_SE3:QUAT 2047 40.6841 6.70497 -84.3567 -0.636767 0.39354 -0.662677 0.0226618 +VERTEX_SE3:QUAT 2048 39.8036 5.08866 -81.2956 -0.627795 0.367489 -0.686068 -0.0116648 +VERTEX_SE3:QUAT 2049 39.1311 3.7359 -78.0687 -0.614043 0.333192 -0.71347 -0.0538074 +VERTEX_SE3:QUAT 2050 38.3693 2.59643 -74.7358 -0.605415 0.30386 -0.729438 -0.0951981 +VERTEX_SE3:QUAT 2051 37.4377 1.85848 -71.3603 -0.601372 0.251189 -0.74086 -0.162426 +VERTEX_SE3:QUAT 2052 36.7601 1.86598 -67.7834 -0.585453 0.227809 -0.752604 -0.19732 +VERTEX_SE3:QUAT 2053 35.8365 2.28949 -64.6075 -0.566769 0.188755 -0.766177 -0.236889 +VERTEX_SE3:QUAT 2054 35.0201 3.0538 -61.4847 -0.54855 0.169563 -0.776102 -0.260781 +VERTEX_SE3:QUAT 2055 34.2695 4.02817 -58.1086 -0.530638 0.136243 -0.787536 -0.282222 +VERTEX_SE3:QUAT 2056 33.5013 5.45893 -54.9892 -0.50982 0.0957194 -0.784868 -0.338976 +VERTEX_SE3:QUAT 2057 32.7525 7.16455 -52.1736 -0.490184 0.0448174 -0.776301 -0.393787 +VERTEX_SE3:QUAT 2058 32.1631 9.36035 -49.3749 -0.476295 0.00913206 -0.761851 -0.438911 +VERTEX_SE3:QUAT 2059 31.6747 11.796 -46.7989 -0.442496 -0.0317673 -0.758159 -0.477894 +VERTEX_SE3:QUAT 2060 31.1956 14.5329 -44.7863 -0.414774 -0.0971854 -0.726983 -0.538529 +VERTEX_SE3:QUAT 2061 31.0246 17.5694 -43.2918 -0.386834 -0.117376 -0.730878 -0.549909 +VERTEX_SE3:QUAT 2062 30.9146 20.818 -41.9799 -0.357239 -0.159702 -0.711626 -0.583493 +VERTEX_SE3:QUAT 2063 30.8876 24.4438 -41.1052 -0.319591 -0.200195 -0.684658 -0.62372 +VERTEX_SE3:QUAT 2064 31.0439 27.8216 -40.6823 -0.281116 -0.248727 -0.639889 -0.67056 +VERTEX_SE3:QUAT 2065 31.2836 31.1459 -40.986 -0.260825 -0.280427 -0.642914 -0.663319 +VERTEX_SE3:QUAT 2066 31.4893 34.5088 -41.3337 -0.219272 -0.316368 -0.602488 -0.69917 +VERTEX_SE3:QUAT 2067 31.548 37.741 -42.2688 -0.188419 -0.360842 -0.564088 -0.718398 +VERTEX_SE3:QUAT 2068 31.9047 40.8558 -43.5096 -0.156076 -0.390536 -0.53923 -0.729625 +VERTEX_SE3:QUAT 2069 32.4673 43.7793 -45.0643 -0.12076 -0.41728 -0.511702 -0.741253 +VERTEX_SE3:QUAT 2070 33.0065 46.4275 -47.0365 -0.0806667 -0.443625 -0.478519 -0.753465 +VERTEX_SE3:QUAT 2071 33.3188 49.0313 -49.132 -0.0438304 -0.474945 -0.456776 -0.750908 +VERTEX_SE3:QUAT 2072 33.7357 51.1697 -51.6587 -0.0106774 -0.505188 -0.434111 -0.7458 +VERTEX_SE3:QUAT 2073 34.0994 53.197 -54.3693 0.0236548 -0.532508 -0.405291 -0.742708 +VERTEX_SE3:QUAT 2074 34.3972 54.7437 -57.2233 0.0562855 -0.557191 -0.369036 -0.741743 +VERTEX_SE3:QUAT 2075 34.6043 56.0027 -60.3526 0.0877909 -0.581951 -0.333964 -0.73627 +VERTEX_SE3:QUAT 2076 35.0899 57.0436 -63.2422 0.120946 -0.605134 -0.302572 -0.726385 +VERTEX_SE3:QUAT 2077 35.1359 57.7534 -66.3661 0.169386 -0.627756 -0.244173 -0.719451 +VERTEX_SE3:QUAT 2078 35.3453 58.0479 -69.6239 0.208815 -0.649585 -0.204213 -0.701949 +VERTEX_SE3:QUAT 2079 35.6852 57.6839 -72.9778 0.245209 -0.662512 -0.166872 -0.687826 +VERTEX_SE3:QUAT 2080 35.856 57.1309 -76.2729 0.281909 -0.674393 -0.136403 -0.668667 +VERTEX_SE3:QUAT 2081 36.2136 56.1801 -79.4284 0.314032 -0.685638 -0.105808 -0.648143 +VERTEX_SE3:QUAT 2082 36.2336 55.0846 -82.3461 0.34959 -0.687332 -0.0595605 -0.633888 +VERTEX_SE3:QUAT 2083 36.5583 53.5641 -85.3619 0.384361 -0.686209 -0.0172843 -0.617321 +VERTEX_SE3:QUAT 2084 36.7987 51.6486 -87.9189 0.408643 -0.692452 0.0196302 -0.594252 +VERTEX_SE3:QUAT 2085 37.016 49.4375 -90.4315 0.435613 -0.692185 0.0621282 -0.572068 +VERTEX_SE3:QUAT 2086 37.0335 47.0726 -92.7339 0.480039 -0.681744 0.124947 -0.537751 +VERTEX_SE3:QUAT 2087 37.1646 44.336 -94.5291 0.5289 -0.6606 0.182885 -0.500426 +VERTEX_SE3:QUAT 2088 37.3929 41.1644 -95.6123 0.571678 -0.630509 0.245228 -0.464225 +VERTEX_SE3:QUAT 2089 37.6426 37.8713 -96.3408 0.587594 -0.629066 0.272712 -0.429695 +VERTEX_SE3:QUAT 2090 37.7571 34.5957 -96.7775 0.622376 -0.600634 0.318809 -0.387618 +VERTEX_SE3:QUAT 2091 38.1018 31.4553 -96.7245 0.640369 -0.584518 0.347324 -0.357256 +VERTEX_SE3:QUAT 2092 38.2345 28.0285 -96.3674 0.652116 -0.570553 0.381721 -0.321719 +VERTEX_SE3:QUAT 2093 38.3654 24.9503 -95.6255 0.688563 -0.52051 0.422261 -0.27685 +VERTEX_SE3:QUAT 2094 38.7376 21.8946 -94.6119 0.709731 -0.475966 0.466481 -0.228326 +VERTEX_SE3:QUAT 2095 39.1726 19.0066 -92.8208 0.711233 -0.452886 0.501718 -0.193189 +VERTEX_SE3:QUAT 2096 39.5328 16.52 -90.8246 0.714806 -0.419529 0.538541 -0.151726 +VERTEX_SE3:QUAT 2097 39.6336 14.4424 -88.6614 0.718283 -0.386991 0.568297 -0.106518 +VERTEX_SE3:QUAT 2098 39.9101 12.5554 -86.0006 0.707531 -0.384316 0.58706 -0.0840393 +VERTEX_SE3:QUAT 2099 39.7583 10.8173 -83.3248 0.72698 -0.328364 0.602175 -0.0326009 +VERTEX_SE3:QUAT 2100 39.9659 9.35141 -80.5555 0.723356 -0.288465 0.62719 0.0133031 +VERTEX_SE3:QUAT 2101 40.0507 8.33296 -77.5975 0.720064 -0.227513 0.6521 0.0671705 +VERTEX_SE3:QUAT 2102 40.1592 7.83642 -74.4054 0.711793 -0.169053 0.669558 0.128308 +VERTEX_SE3:QUAT 2103 40.217 7.88073 -71.3088 0.698904 -0.120078 0.682097 0.178486 +VERTEX_SE3:QUAT 2104 40.1816 8.46571 -68.0985 0.686048 -0.0637317 0.688308 0.226953 +VERTEX_SE3:QUAT 2105 40.3506 9.47465 -65.1326 0.669768 -0.0221473 0.697676 0.253314 +VERTEX_SE3:QUAT 2106 40.3558 10.8472 -62.2294 0.645307 0.0268313 0.704965 0.293058 +VERTEX_SE3:QUAT 2107 40.4792 12.4335 -59.5448 0.618801 0.0700875 0.705065 0.339201 +VERTEX_SE3:QUAT 2108 40.4619 14.424 -57.1777 0.585762 0.143914 0.684719 0.409062 +VERTEX_SE3:QUAT 2109 40.4104 16.8367 -55.1204 0.552452 0.19105 0.681547 0.440217 +VERTEX_SE3:QUAT 2110 40.5193 19.4387 -53.5908 0.518699 0.239823 0.669688 0.474293 +VERTEX_SE3:QUAT 2111 40.5759 22.3602 -52.3673 0.488972 0.275494 0.662458 0.496143 +VERTEX_SE3:QUAT 2112 40.4918 25.3088 -51.215 0.458121 0.303431 0.658979 0.513617 +VERTEX_SE3:QUAT 2113 40.3334 28.2273 -50.4566 0.41112 0.350523 0.640635 0.54562 +VERTEX_SE3:QUAT 2114 40.0737 31.4091 -50.2623 0.383095 0.380462 0.637353 0.549789 +VERTEX_SE3:QUAT 2115 39.6661 34.3111 -50.3146 0.344238 0.416498 0.626772 0.561415 +VERTEX_SE3:QUAT 2116 39.1575 37.4111 -50.4693 0.292641 0.459421 0.597811 0.588146 +VERTEX_SE3:QUAT 2117 38.7517 40.2403 -51.2949 0.253431 0.498884 0.57427 0.59758 +VERTEX_SE3:QUAT 2118 38.3903 43.195 -52.296 0.22135 0.534373 0.54626 0.605846 +VERTEX_SE3:QUAT 2119 38.0075 45.9202 -53.7128 0.187824 0.559459 0.535599 0.604038 +VERTEX_SE3:QUAT 2120 37.3306 48.2532 -55.3274 0.139824 0.581745 0.512523 0.615908 +VERTEX_SE3:QUAT 2121 36.565 50.3854 -57.2441 0.104121 0.599168 0.49126 0.623555 +VERTEX_SE3:QUAT 2122 35.8853 52.4897 -59.3627 0.0687084 0.619549 0.460476 0.631981 +VERTEX_SE3:QUAT 2123 35.3409 54.245 -61.5703 0.0275297 0.636962 0.424241 0.643072 +VERTEX_SE3:QUAT 2124 34.8841 55.7725 -64.1857 -0.0367508 0.657992 0.36522 0.657503 +VERTEX_SE3:QUAT 2125 34.5643 56.8963 -67.0552 -0.0825968 0.669582 0.313652 0.668177 +VERTEX_SE3:QUAT 2126 34.2335 57.4918 -70.0277 -0.096753 0.684785 0.307648 0.653499 +VERTEX_SE3:QUAT 2127 33.8998 57.9324 -72.9402 -0.125901 0.705027 0.286461 0.636417 +VERTEX_SE3:QUAT 2128 33.5221 58.1882 -75.9217 -0.141807 0.718839 0.268541 0.625338 +VERTEX_SE3:QUAT 2129 32.9236 58.4923 -78.944 -0.218421 0.724008 0.211328 0.61923 +VERTEX_SE3:QUAT 2130 32.4498 58.0485 -81.9552 -0.25188 0.73178 0.178435 0.60763 +VERTEX_SE3:QUAT 2131 32.1404 57.3393 -84.7489 -0.289921 0.742238 0.151057 0.584987 +VERTEX_SE3:QUAT 2132 31.6546 56.3345 -87.5759 -0.351404 0.735293 0.0907705 0.572381 +VERTEX_SE3:QUAT 2133 31.4782 54.8047 -90.025 -0.391677 0.733265 0.0605176 0.552494 +VERTEX_SE3:QUAT 2134 31.5072 53.1382 -92.5803 -0.437511 0.715726 0.0166533 0.544099 +VERTEX_SE3:QUAT 2135 31.6214 51.0686 -94.8194 -0.455583 0.721044 -0.0128408 0.521895 +VERTEX_SE3:QUAT 2136 31.6936 48.8148 -96.8214 -0.525883 0.684396 -0.0818999 0.498339 +VERTEX_SE3:QUAT 2137 31.9696 46.464 -98.4209 -0.553506 0.673964 -0.117406 0.474994 +VERTEX_SE3:QUAT 2138 32.3287 43.9689 -99.4833 -0.57809 0.659544 -0.156732 0.454146 +VERTEX_SE3:QUAT 2139 32.6605 41.1934 -100.638 -0.609053 0.647116 -0.194933 0.415087 +VERTEX_SE3:QUAT 2140 32.9973 38.2658 -101.308 -0.65759 0.604456 -0.243505 0.37804 +VERTEX_SE3:QUAT 2141 33.4836 35.4482 -101.47 -0.703206 0.556222 -0.296086 0.329319 +VERTEX_SE3:QUAT 2142 34.1995 32.5869 -101.12 -0.721974 0.531599 -0.325352 0.300503 +VERTEX_SE3:QUAT 2143 34.9335 29.8068 -100.481 -0.740538 0.504165 -0.358161 0.262949 +VERTEX_SE3:QUAT 2144 35.651 27.1381 -99.4398 -0.759957 0.462331 -0.395269 0.229081 +VERTEX_SE3:QUAT 2145 36.3477 24.6676 -98.2491 -0.766009 0.432952 -0.435028 0.191136 +VERTEX_SE3:QUAT 2146 37.1246 22.4673 -96.651 -0.765934 0.409032 -0.471058 0.155378 +VERTEX_SE3:QUAT 2147 37.9835 20.5894 -94.787 -0.780239 0.368017 -0.492719 0.114098 +VERTEX_SE3:QUAT 2148 38.6751 18.7565 -92.7385 -0.785609 0.32389 -0.522314 0.0714303 +VERTEX_SE3:QUAT 2149 39.4324 17.2471 -90.4456 -0.789067 0.270126 -0.550967 0.0289762 +VERTEX_SE3:QUAT 2150 40.006 15.9907 -88.0419 -0.789807 0.211569 -0.575379 -0.0195847 +VERTEX_SE3:QUAT 2151 40.7103 15.5206 -85.3492 -0.789874 0.142242 -0.593056 -0.0644205 +VERTEX_SE3:QUAT 2152 41.5693 15.1954 -82.4863 -0.775961 0.108353 -0.615164 -0.0878419 +VERTEX_SE3:QUAT 2153 42.1052 15.36 -79.7184 -0.770275 0.0549068 -0.620678 -0.135719 +VERTEX_SE3:QUAT 2154 42.7044 15.9539 -76.9188 -0.755223 0.0101371 -0.633538 -0.167826 +VERTEX_SE3:QUAT 2155 43.1399 16.7375 -74.2298 -0.735454 -0.0220134 -0.648369 -0.195554 +VERTEX_SE3:QUAT 2156 43.4296 17.6883 -71.7365 -0.715256 -0.08506 -0.6447 -0.256 +VERTEX_SE3:QUAT 2157 43.8775 19.209 -69.3809 -0.69359 -0.125637 -0.650608 -0.282589 +VERTEX_SE3:QUAT 2158 44.0319 20.9251 -67.2264 -0.672314 -0.163271 -0.656707 -0.300121 +VERTEX_SE3:QUAT 2159 44.0814 22.6427 -65.2118 -0.639284 -0.219538 -0.651527 -0.344429 +VERTEX_SE3:QUAT 2160 44.1753 24.9057 -63.591 -0.622186 -0.229405 -0.656587 -0.359376 +VERTEX_SE3:QUAT 2161 44.2267 27.1255 -62.1459 -0.59022 -0.259238 -0.663403 -0.379912 +VERTEX_SE3:QUAT 2162 44.1645 29.4237 -60.8135 -0.549612 -0.312486 -0.653797 -0.415727 +VERTEX_SE3:QUAT 2163 43.9856 32.0754 -59.9224 -0.504926 -0.355943 -0.644516 -0.450504 +VERTEX_SE3:QUAT 2164 43.8465 34.6006 -59.3194 -0.46292 -0.396477 -0.630737 -0.480295 +VERTEX_SE3:QUAT 2165 43.5226 37.1895 -59.059 -0.418927 -0.43037 -0.624583 -0.499177 +VERTEX_SE3:QUAT 2166 43.2411 39.8698 -59.0548 -0.381388 -0.465471 -0.60462 -0.521837 +VERTEX_SE3:QUAT 2167 42.8685 42.6532 -59.2605 -0.350536 -0.48478 -0.609024 -0.520771 +VERTEX_SE3:QUAT 2168 42.3345 45.3461 -59.5706 -0.30396 -0.518249 -0.580674 -0.549404 +VERTEX_SE3:QUAT 2169 41.7167 47.7328 -60.5085 -0.264286 -0.553041 -0.555617 -0.561773 +VERTEX_SE3:QUAT 2170 41.2138 50.1543 -61.6041 -0.214538 -0.586029 -0.518715 -0.584362 +VERTEX_SE3:QUAT 2171 40.7547 52.3516 -62.8464 -0.168816 -0.610376 -0.482577 -0.605031 +VERTEX_SE3:QUAT 2172 40.1815 54.2607 -64.5849 -0.127401 -0.636456 -0.452247 -0.611691 +VERTEX_SE3:QUAT 2173 39.6063 55.9683 -66.4295 -0.0690541 -0.660005 -0.415937 -0.621789 +VERTEX_SE3:QUAT 2174 38.9207 57.4769 -68.679 -0.022008 -0.678779 -0.377991 -0.629203 +VERTEX_SE3:QUAT 2175 38.3605 58.5607 -70.9535 0.0297377 -0.697484 -0.34842 -0.625489 +VERTEX_SE3:QUAT 2176 37.6973 59.3666 -73.3352 0.083011 -0.708892 -0.319855 -0.623117 +VERTEX_SE3:QUAT 2177 37.104 60.0561 -75.966 0.138993 -0.72062 -0.274964 -0.621114 +VERTEX_SE3:QUAT 2178 36.6929 60.1783 -78.6573 0.170736 -0.727739 -0.258501 -0.611901 +VERTEX_SE3:QUAT 2179 36.325 60.1428 -81.1961 0.186658 -0.745373 -0.239847 -0.593339 +VERTEX_SE3:QUAT 2180 35.7984 59.799 -83.6811 0.263047 -0.744188 -0.186445 -0.585003 +VERTEX_SE3:QUAT 2181 35.3527 59.183 -86.2062 0.307452 -0.741882 -0.148755 -0.577024 +VERTEX_SE3:QUAT 2182 35.0885 58.2457 -88.6378 0.357138 -0.735966 -0.107347 -0.565051 +VERTEX_SE3:QUAT 2183 34.8701 57.0847 -90.8094 0.404293 -0.733663 -0.0680172 -0.541904 +VERTEX_SE3:QUAT 2184 34.7761 55.6248 -92.9744 0.46772 -0.710143 -0.0143003 -0.526052 +VERTEX_SE3:QUAT 2185 34.8735 53.8972 -94.964 0.52166 -0.687451 0.0379146 -0.50383 +VERTEX_SE3:QUAT 2186 35.0458 51.8398 -96.5272 0.553459 -0.681649 0.0688881 -0.473595 +VERTEX_SE3:QUAT 2187 35.3027 49.489 -97.8759 0.598771 -0.647948 0.117815 -0.455803 +VERTEX_SE3:QUAT 2188 35.8176 47.137 -99.0297 0.622055 -0.632691 0.149327 -0.436408 +VERTEX_SE3:QUAT 2189 36.2784 44.876 -99.7427 0.643044 -0.615968 0.18264 -0.416797 +VERTEX_SE3:QUAT 2190 36.8994 42.3637 -100.116 0.674833 -0.578977 0.231092 -0.394945 +VERTEX_SE3:QUAT 2191 37.5753 39.8805 -100.24 0.694777 -0.552739 0.269795 -0.372794 +VERTEX_SE3:QUAT 2192 38.1808 37.4286 -100.121 0.709438 -0.526451 0.310516 -0.350894 +VERTEX_SE3:QUAT 2193 38.7934 34.9782 -99.8649 0.73227 -0.484 0.359427 -0.316758 +VERTEX_SE3:QUAT 2194 39.5494 32.695 -99.3044 0.754939 -0.439322 0.399496 -0.278327 +VERTEX_SE3:QUAT 2195 40.3712 30.5285 -98.2113 0.764716 -0.405271 0.43384 -0.250493 +VERTEX_SE3:QUAT 2196 41.1381 28.5277 -96.9258 0.759391 -0.395306 0.458778 -0.23787 +VERTEX_SE3:QUAT 2197 41.7976 26.4189 -95.2762 0.777928 -0.345896 0.489511 -0.188581 +VERTEX_SE3:QUAT 2198 42.5166 24.7019 -93.5273 0.77004 -0.331595 0.516915 -0.172864 +VERTEX_SE3:QUAT 2199 43.001 23.1714 -91.6652 0.778793 -0.290113 0.538303 -0.139806 +VERTEX_SE3:QUAT 2200 43.7763 21.7142 -89.7109 0.785201 -0.237112 0.563468 -0.0986942 +VERTEX_SE3:QUAT 2201 44.4819 20.6195 -87.526 0.784398 -0.192377 0.586413 -0.0618987 +VERTEX_SE3:QUAT 2202 44.9804 19.9472 -85.3536 0.77575 -0.152949 0.611667 -0.0260963 +VERTEX_SE3:QUAT 2203 45.3863 19.5177 -83.052 0.768102 -0.102847 0.632013 0.0011713 +VERTEX_SE3:QUAT 2204 45.8128 19.3605 -80.5183 0.7532 -0.0565774 0.654417 0.0350192 +VERTEX_SE3:QUAT 2205 46.1129 19.4245 -78.0452 0.738738 -0.000979695 0.667854 0.0907555 +VERTEX_SE3:QUAT 2206 46.2673 19.9609 -75.56 0.721584 0.0247597 0.681698 0.118283 +VERTEX_SE3:QUAT 2207 46.3524 20.7005 -73.232 0.694377 0.0773613 0.695449 0.16795 +VERTEX_SE3:QUAT 2208 46.563 21.6086 -71.0889 0.674829 0.111319 0.704634 0.188957 +VERTEX_SE3:QUAT 2209 46.4514 22.8238 -69.1147 0.65218 0.145409 0.709546 0.223745 +VERTEX_SE3:QUAT 2210 46.3651 24.2351 -67.0961 0.636131 0.17051 0.71439 0.236453 +VERTEX_SE3:QUAT 2211 46.1613 25.7947 -65.1289 0.61196 0.188609 0.729215 0.241199 +VERTEX_SE3:QUAT 2212 45.7558 27.3088 -63.1864 0.587629 0.224396 0.727299 0.274545 +VERTEX_SE3:QUAT 2213 45.434 29.0085 -61.5296 0.555986 0.247278 0.733331 0.303246 +VERTEX_SE3:QUAT 2214 44.8784 30.8125 -59.9804 0.522724 0.282604 0.730792 0.335914 +VERTEX_SE3:QUAT 2215 44.2598 32.6016 -58.8757 0.48673 0.320273 0.71913 0.378644 +VERTEX_SE3:QUAT 2216 43.7239 34.6825 -57.7726 0.446873 0.343876 0.72328 0.398647 +VERTEX_SE3:QUAT 2217 43.1499 36.8365 -57.3228 0.407166 0.375103 0.710672 0.434119 +VERTEX_SE3:QUAT 2218 42.7829 39.0596 -56.8071 0.365438 0.406784 0.692919 0.469941 +VERTEX_SE3:QUAT 2219 42.2356 41.2016 -56.5822 0.332781 0.429307 0.692514 0.474739 +VERTEX_SE3:QUAT 2220 41.5105 43.3857 -56.7493 0.309545 0.449528 0.681077 0.488099 +VERTEX_SE3:QUAT 2221 40.6826 45.6402 -56.8918 0.280369 0.474421 0.666576 0.501991 +VERTEX_SE3:QUAT 2222 39.9573 47.9032 -57.3613 0.21279 0.508532 0.619254 0.559143 +VERTEX_SE3:QUAT 2223 39.3639 49.8359 -58.3101 0.170383 0.529024 0.594108 0.581497 +VERTEX_SE3:QUAT 2224 38.9021 51.9421 -59.2677 0.134874 0.541632 0.56969 0.603239 +VERTEX_SE3:QUAT 2225 38.3195 53.7916 -60.9072 0.108913 0.56626 0.547394 0.606504 +VERTEX_SE3:QUAT 2226 37.6665 55.5009 -62.4548 0.0682492 0.586289 0.514992 0.621603 +VERTEX_SE3:QUAT 2227 37.4006 57.1208 -64.0468 0.029797 0.60738 0.475096 0.635992 +VERTEX_SE3:QUAT 2228 37.2266 58.345 -65.8226 -0.00339571 0.625715 0.447754 0.638737 +VERTEX_SE3:QUAT 2229 36.8743 59.4347 -67.7696 -0.0389875 0.638099 0.420727 0.64366 +VERTEX_SE3:QUAT 2230 36.5661 60.4223 -69.6517 -0.0860363 0.649148 0.378954 0.653911 +VERTEX_SE3:QUAT 2231 36.2178 61.1129 -71.7934 -0.111793 0.668939 0.363553 0.638633 +VERTEX_SE3:QUAT 2232 35.9654 61.6022 -73.9404 -0.153718 0.682616 0.333322 0.631904 +VERTEX_SE3:QUAT 2233 35.7743 61.8465 -76.2468 -0.192443 0.69616 0.29778 0.624223 +VERTEX_SE3:QUAT 2234 35.3731 61.977 -78.5542 -0.24274 0.697374 0.240212 0.630115 +VERTEX_SE3:QUAT 2235 35.2945 61.715 -80.6535 -0.283336 0.691422 0.203212 0.632741 +VERTEX_SE3:QUAT 2236 35.4105 61.0842 -82.7808 -0.341992 0.68394 0.15917 0.624445 +VERTEX_SE3:QUAT 2237 35.4909 60.2309 -84.9228 -0.366041 0.688771 0.137333 0.610531 +VERTEX_SE3:QUAT 2238 35.4345 59.3642 -86.9698 -0.414499 0.677926 0.0836673 0.601337 +VERTEX_SE3:QUAT 2239 36.006 58.2103 -88.7392 -0.481117 0.64685 0.0194009 0.591384 +VERTEX_SE3:QUAT 2240 36.345 56.8212 -90.3392 -0.52795 0.620567 -0.0259381 0.579217 +VERTEX_SE3:QUAT 2241 36.8026 55.1363 -91.8076 -0.568343 0.598267 -0.0772619 0.559547 +VERTEX_SE3:QUAT 2242 37.5122 53.2658 -93.1463 -0.602652 0.571044 -0.117451 0.544908 +VERTEX_SE3:QUAT 2243 38.386 51.3946 -93.9611 -0.642138 0.532868 -0.17115 0.523849 +VERTEX_SE3:QUAT 2244 39.1476 49.4442 -94.3711 -0.663434 0.513126 -0.20855 0.503055 +VERTEX_SE3:QUAT 2245 40.0314 47.4693 -94.8073 -0.662871 0.516913 -0.23333 0.488835 +VERTEX_SE3:QUAT 2246 40.8708 45.5225 -94.9954 -0.667858 0.509219 -0.260359 0.476313 +VERTEX_SE3:QUAT 2247 41.7284 43.5841 -94.9103 -0.69681 0.46428 -0.321203 0.442413 +VERTEX_SE3:QUAT 2248 42.4245 41.5437 -94.5206 -0.714856 0.432423 -0.364572 0.411191 +VERTEX_SE3:QUAT 2249 43.2468 39.61 -94.0709 -0.735475 0.396635 -0.409357 0.36631 +VERTEX_SE3:QUAT 2250 43.9784 37.8571 -93.4096 -0.752195 0.346772 -0.454964 0.327047 +VERTEX_SE3:QUAT 2251 44.6775 36.1934 -92.264 -0.761159 0.301675 -0.493823 0.292862 +VERTEX_SE3:QUAT 2252 45.5446 34.6555 -91.1383 -0.763225 0.269666 -0.523343 0.266231 +VERTEX_SE3:QUAT 2253 46.1974 33.3011 -89.6305 -0.773362 0.212928 -0.555614 0.218783 +VERTEX_SE3:QUAT 2254 47.014 32.2708 -87.7902 -0.773895 0.163171 -0.588039 0.169325 +VERTEX_SE3:QUAT 2255 47.5714 31.5817 -85.9542 -0.774427 0.123896 -0.607287 0.126948 +VERTEX_SE3:QUAT 2256 47.9772 31.0902 -84.1091 -0.770427 0.0627007 -0.62977 0.0768171 +VERTEX_SE3:QUAT 2257 48.3854 31.0029 -82.0735 -0.748921 0.060025 -0.656823 0.064012 +VERTEX_SE3:QUAT 2258 48.5268 30.9993 -80.0685 -0.740515 0.0395249 -0.669935 0.0355218 +VERTEX_SE3:QUAT 2259 48.5379 30.9083 -78.1593 -0.727129 0.0139962 -0.686279 0.0104564 +VERTEX_SE3:QUAT 2260 48.5188 30.929 -76.1339 -0.714254 -0.00781924 -0.69974 -0.0119629 +VERTEX_SE3:QUAT 2261 48.3989 31.0615 -74.0094 -0.703586 -0.0374077 -0.708491 -0.0400967 +VERTEX_SE3:QUAT 2262 48.2519 31.3963 -72.1323 -0.683749 -0.0909984 -0.719458 -0.0811572 +VERTEX_SE3:QUAT 2263 48.0743 31.9805 -70.2269 -0.651442 -0.151547 -0.731975 -0.12988 +VERTEX_SE3:QUAT 2264 47.7329 32.9908 -68.4236 -0.624537 -0.204993 -0.732483 -0.177203 +VERTEX_SE3:QUAT 2265 47.3947 34.1415 -66.8228 -0.58911 -0.257839 -0.729982 -0.231504 +VERTEX_SE3:QUAT 2266 46.8044 35.5584 -65.4901 -0.559242 -0.294248 -0.727153 -0.26817 +VERTEX_SE3:QUAT 2267 46.2519 37.0856 -64.4072 -0.523756 -0.324243 -0.728484 -0.299762 +VERTEX_SE3:QUAT 2268 45.5847 38.7123 -63.3854 -0.485442 -0.372518 -0.711907 -0.344623 +VERTEX_SE3:QUAT 2269 45.0789 40.468 -62.7356 -0.463649 -0.39248 -0.701817 -0.372077 +VERTEX_SE3:QUAT 2270 44.4674 42.3267 -62.1265 -0.42487 -0.429732 -0.683997 -0.408613 +VERTEX_SE3:QUAT 2271 43.8537 44.4104 -61.8658 -0.375748 -0.475843 -0.657024 -0.448003 +VERTEX_SE3:QUAT 2272 43.1187 46.2783 -61.9249 -0.340995 -0.500933 -0.64187 -0.469884 +VERTEX_SE3:QUAT 2273 42.6361 48.1248 -62.1115 -0.297865 -0.527833 -0.615395 -0.503941 +VERTEX_SE3:QUAT 2274 41.9725 49.8984 -62.5561 -0.26522 -0.543914 -0.599468 -0.523884 +VERTEX_SE3:QUAT 2275 41.4787 51.7478 -63.144 -0.231745 -0.563145 -0.590735 -0.529334 +VERTEX_SE3:QUAT 2276 40.8907 53.4882 -63.9629 -0.201729 -0.578243 -0.572877 -0.54475 +VERTEX_SE3:QUAT 2277 40.2481 55.1702 -65.0137 -0.164999 -0.598791 -0.551987 -0.556359 +VERTEX_SE3:QUAT 2278 39.7054 56.392 -66.0994 -0.113397 -0.616058 -0.524703 -0.576454 +VERTEX_SE3:QUAT 2279 39.2591 57.7288 -67.4626 -0.0775208 -0.640099 -0.495697 -0.58185 +VERTEX_SE3:QUAT 2280 38.7324 59.0536 -69.0345 -0.0248895 -0.654227 -0.444652 -0.611271 +VERTEX_SE3:QUAT 2281 38.275 60.0477 -70.6011 0.0377742 -0.66109 -0.400087 -0.633612 +VERTEX_SE3:QUAT 2282 38.0313 60.8471 -72.3224 0.0995828 -0.668055 -0.353898 -0.646948 +VERTEX_SE3:QUAT 2283 37.8189 61.4082 -74.2429 0.133271 -0.674093 -0.322093 -0.651225 +VERTEX_SE3:QUAT 2284 37.6484 61.5931 -76.0686 0.172018 -0.679297 -0.287793 -0.652795 +VERTEX_SE3:QUAT 2285 37.6164 61.8355 -77.7637 0.195824 -0.685394 -0.26228 -0.65046 +VERTEX_SE3:QUAT 2286 37.4732 61.8621 -79.5402 0.228649 -0.689597 -0.224446 -0.649461 +VERTEX_SE3:QUAT 2287 37.598 61.5064 -81.5275 0.259336 -0.689642 -0.187465 -0.649611 +VERTEX_SE3:QUAT 2288 37.4911 60.9759 -83.2726 0.281651 -0.688269 -0.157961 -0.649621 +VERTEX_SE3:QUAT 2289 37.618 60.4479 -85.2082 0.323845 -0.684776 -0.122577 -0.641234 +VERTEX_SE3:QUAT 2290 37.5642 59.79 -86.8434 0.352253 -0.683547 -0.0900447 -0.632908 +VERTEX_SE3:QUAT 2291 37.625 59.1821 -88.4163 0.408358 -0.665861 -0.0225741 -0.62399 +VERTEX_SE3:QUAT 2292 37.9324 58.1493 -89.7106 0.448664 -0.659617 0.0143905 -0.602826 +VERTEX_SE3:QUAT 2293 38.2344 56.6137 -91.0444 0.4766 -0.650249 0.0488005 -0.589616 +VERTEX_SE3:QUAT 2294 38.5724 55.3242 -92.1946 0.512199 -0.635505 0.102559 -0.568566 +VERTEX_SE3:QUAT 2295 39.0217 53.7262 -93.2136 0.533679 -0.623146 0.133824 -0.555848 +VERTEX_SE3:QUAT 2296 39.4058 52.233 -94.0939 0.566849 -0.601532 0.178413 -0.533863 +VERTEX_SE3:QUAT 2297 39.8432 50.5715 -94.7243 0.598003 -0.575011 0.211303 -0.516823 +VERTEX_SE3:QUAT 2298 40.3273 48.963 -95.2955 0.622323 -0.556696 0.242985 -0.493722 +VERTEX_SE3:QUAT 2299 40.944 47.4037 -95.4696 0.662964 -0.512065 0.299615 -0.456617 +VERTEX_SE3:QUAT 2300 41.444 45.6807 -95.2403 0.691304 -0.472252 0.336089 -0.431417 +VERTEX_SE3:QUAT 2301 41.9759 44.0572 -94.9401 0.72189 -0.417726 0.386517 -0.393681 +VERTEX_SE3:QUAT 2302 42.6653 42.498 -94.3228 0.743968 -0.376006 0.414063 -0.365625 +VERTEX_SE3:QUAT 2303 43.5093 41.1246 -93.5621 0.757512 -0.33356 0.457428 -0.325074 +VERTEX_SE3:QUAT 2304 44.1109 39.7988 -92.546 0.756821 -0.327329 0.477923 -0.302766 +VERTEX_SE3:QUAT 2305 44.7408 38.5253 -91.353 0.77578 -0.253496 0.520055 -0.251887 +VERTEX_SE3:QUAT 2306 45.2071 37.3957 -90.1074 0.7668 -0.245526 0.539033 -0.247342 +VERTEX_SE3:QUAT 2307 45.797 36.3904 -88.7148 0.770385 -0.194683 0.57064 -0.207304 +VERTEX_SE3:QUAT 2308 46.2172 35.677 -87.364 0.773807 -0.145635 0.595147 -0.160665 +VERTEX_SE3:QUAT 2309 46.5099 34.8852 -85.9442 0.770423 -0.101838 0.616392 -0.127037 +VERTEX_SE3:QUAT 2310 46.9556 34.6084 -84.4277 0.763804 -0.0533972 0.638135 -0.0808417 +VERTEX_SE3:QUAT 2311 47.1652 34.6054 -82.7346 0.754231 -0.0207429 0.654801 -0.0440555 +VERTEX_SE3:QUAT 2312 47.167 34.5863 -81.138 0.741689 0.0137239 0.670516 -0.0108814 +VERTEX_SE3:QUAT 2313 47.2913 34.8485 -79.5941 0.728779 0.0670782 0.680484 0.0363662 +VERTEX_SE3:QUAT 2314 47.2844 35.307 -77.954 0.717423 0.0898291 0.688271 0.0593137 +VERTEX_SE3:QUAT 2315 47.3464 35.722 -76.3116 0.69501 0.134329 0.700586 0.0899835 +VERTEX_SE3:QUAT 2316 47.1855 36.4897 -74.947 0.673019 0.180508 0.705107 0.131475 +VERTEX_SE3:QUAT 2317 47.1285 37.183 -73.5193 0.652644 0.199397 0.714674 0.153423 +VERTEX_SE3:QUAT 2318 47.0067 38.2331 -72.2144 0.615578 0.244218 0.721319 0.202781 +VERTEX_SE3:QUAT 2319 46.6196 39.4173 -71.0308 0.58238 0.29379 0.716803 0.246403 +VERTEX_SE3:QUAT 2320 46.2611 40.5353 -69.9526 0.564068 0.31774 0.72043 0.248694 +VERTEX_SE3:QUAT 2321 45.8005 41.665 -68.901 0.520392 0.373286 0.698041 0.320295 +VERTEX_SE3:QUAT 2322 45.2451 43.0288 -68.1775 0.482643 0.413314 0.676636 0.372009 +VERTEX_SE3:QUAT 2323 44.9412 44.4091 -67.7615 0.442057 0.454026 0.661271 0.401455 +VERTEX_SE3:QUAT 2324 44.6354 45.9391 -67.6536 0.41361 0.468908 0.660264 0.416057 +VERTEX_SE3:QUAT 2325 44.0341 47.3601 -67.6979 0.389813 0.486526 0.654437 0.427843 +VERTEX_SE3:QUAT 2326 43.7854 48.858 -67.6785 0.348114 0.512614 0.638317 0.456722 +VERTEX_SE3:QUAT 2327 43.2732 50.2987 -67.7905 0.302878 0.544513 0.607458 0.492712 +VERTEX_SE3:QUAT 2328 42.9328 51.5485 -68.345 0.260129 0.570583 0.580274 0.519664 +VERTEX_SE3:QUAT 2329 42.3817 52.8997 -69.153 0.227105 0.587107 0.560689 0.537919 +VERTEX_SE3:QUAT 2330 41.9326 54.0946 -69.7152 0.192002 0.596411 0.554953 0.547226 +VERTEX_SE3:QUAT 2331 41.4263 55.3148 -70.2959 0.129402 0.618817 0.506415 0.586399 +VERTEX_SE3:QUAT 2332 41.0048 56.5161 -71.4033 0.0716104 0.632737 0.472385 0.6094 +VERTEX_SE3:QUAT 2333 40.6903 57.3936 -72.5689 0.0359584 0.645287 0.445279 0.619708 +VERTEX_SE3:QUAT 2334 40.5162 58.0599 -73.8409 -0.00847024 0.655741 0.402478 0.638705 +VERTEX_SE3:QUAT 2335 40.2867 58.7138 -75.0155 -0.0644943 0.669411 0.353451 0.650232 +VERTEX_SE3:QUAT 2336 40.0574 59.1173 -76.385 -0.107879 0.667779 0.310604 0.667801 +VERTEX_SE3:QUAT 2337 40.0044 59.3656 -77.7533 -0.136881 0.669102 0.271356 0.678183 +VERTEX_SE3:QUAT 2338 39.8674 59.5303 -79.2475 -0.196585 0.672525 0.20831 0.682401 +VERTEX_SE3:QUAT 2339 39.9337 59.3731 -80.7532 -0.21815 0.677595 0.189606 0.676258 +VERTEX_SE3:QUAT 2340 40.0486 59.064 -82.2254 -0.251236 0.682384 0.148489 0.670211 +VERTEX_SE3:QUAT 2341 39.9834 58.6892 -83.5521 -0.286586 0.680337 0.104746 0.666362 +VERTEX_SE3:QUAT 2342 40.0857 58.1116 -84.9816 -0.332075 0.676167 0.0602387 0.654902 +VERTEX_SE3:QUAT 2343 40.2588 57.5049 -86.4085 -0.383681 0.65728 -0.000382395 0.648669 +VERTEX_SE3:QUAT 2344 40.6088 56.6432 -87.5875 -0.413461 0.646353 -0.0433148 0.639845 +VERTEX_SE3:QUAT 2345 41.0692 55.6947 -88.5914 -0.488879 0.599027 -0.12263 0.622194 +VERTEX_SE3:QUAT 2346 41.4169 54.5194 -89.3431 -0.541747 0.552534 -0.188412 0.604746 +VERTEX_SE3:QUAT 2347 41.9985 53.2177 -89.7442 -0.572583 0.528899 -0.23627 0.580165 +VERTEX_SE3:QUAT 2348 42.4425 51.927 -90.0557 -0.61597 0.485242 -0.296759 0.545028 +VERTEX_SE3:QUAT 2349 42.9697 50.5 -90.2348 -0.624664 0.487236 -0.31111 0.524983 +VERTEX_SE3:QUAT 2350 43.4882 49.4151 -90.134 -0.632076 0.484288 -0.336975 0.502388 +VERTEX_SE3:QUAT 2351 43.9412 47.9843 -90.2039 -0.648771 0.459364 -0.372262 0.479065 +VERTEX_SE3:QUAT 2352 44.3888 46.5452 -90.0515 -0.669731 0.415064 -0.415286 0.454664 +VERTEX_SE3:QUAT 2353 44.7862 45.3592 -89.8212 -0.684865 0.383978 -0.45347 0.421764 +VERTEX_SE3:QUAT 2354 45.1874 44.0357 -89.1119 -0.705817 0.339184 -0.493277 0.378753 +VERTEX_SE3:QUAT 2355 45.4962 42.9952 -88.266 -0.716017 0.304352 -0.521934 0.349677 +VERTEX_SE3:QUAT 2356 45.8457 42.0552 -87.437 -0.734755 0.245354 -0.561166 0.291596 +VERTEX_SE3:QUAT 2357 46.0543 41.1395 -86.3326 -0.737124 0.216052 -0.586922 0.255917 +VERTEX_SE3:QUAT 2358 46.4621 40.4181 -85.1924 -0.736928 0.17793 -0.616867 0.211551 +VERTEX_SE3:QUAT 2359 46.7995 39.8203 -84.0577 -0.734945 0.134476 -0.63972 0.180363 +VERTEX_SE3:QUAT 2360 47.0502 39.4322 -82.8643 -0.726619 0.0715596 -0.671271 0.127665 +VERTEX_SE3:QUAT 2361 47.1119 39.2013 -81.7494 -0.720206 0.0271649 -0.688097 0.084188 +VERTEX_SE3:QUAT 2362 47.1174 39.2553 -80.3731 -0.719219 -0.0189919 -0.693641 0.0349959 +VERTEX_SE3:QUAT 2363 47.2153 39.4817 -78.896 -0.709918 -0.0492689 -0.702466 0.0114171 +VERTEX_SE3:QUAT 2364 47.1923 39.6623 -77.7095 -0.691837 -0.105504 -0.71286 -0.0454006 +VERTEX_SE3:QUAT 2365 47.3417 40.1874 -76.3417 -0.668204 -0.142973 -0.724739 -0.0884124 +VERTEX_SE3:QUAT 2366 47.3384 40.7161 -75.1726 -0.6504 -0.180976 -0.725108 -0.135812 +VERTEX_SE3:QUAT 2367 47.1435 41.467 -74.1197 -0.629859 -0.219813 -0.723067 -0.17926 +VERTEX_SE3:QUAT 2368 46.9129 42.2775 -73.1828 -0.600093 -0.271552 -0.715331 -0.233343 +VERTEX_SE3:QUAT 2369 46.8126 43.31 -72.1945 -0.568307 -0.322131 -0.702089 -0.283424 +VERTEX_SE3:QUAT 2370 46.37 44.2573 -71.6834 -0.550057 -0.348141 -0.697806 -0.298833 +VERTEX_SE3:QUAT 2371 46.0798 45.3516 -71.2352 -0.506521 -0.391039 -0.684724 -0.348824 +VERTEX_SE3:QUAT 2372 45.9093 46.416 -70.6904 -0.467471 -0.426553 -0.663534 -0.399057 +VERTEX_SE3:QUAT 2373 45.4741 47.8081 -70.4785 -0.434681 -0.457526 -0.642943 -0.433989 +VERTEX_SE3:QUAT 2374 45.1505 48.9327 -70.2937 -0.394467 -0.494671 -0.607011 -0.480868 +VERTEX_SE3:QUAT 2375 44.8776 50.1203 -70.5665 -0.351372 -0.528825 -0.577211 -0.513527 +VERTEX_SE3:QUAT 2376 44.329 51.2444 -71.0036 -0.315717 -0.550242 -0.555436 -0.537632 +VERTEX_SE3:QUAT 2377 44.1651 52.3125 -71.4966 -0.256959 -0.574258 -0.511812 -0.58502 +VERTEX_SE3:QUAT 2378 44.0041 53.2021 -71.9845 -0.204305 -0.60042 -0.469631 -0.614168 +VERTEX_SE3:QUAT 2379 43.7066 53.9314 -72.7832 -0.162416 -0.615771 -0.433351 -0.637694 +VERTEX_SE3:QUAT 2380 43.7762 54.7703 -73.5438 -0.153762 -0.625334 -0.425036 -0.636129 +VERTEX_SE3:QUAT 2381 43.7258 55.5075 -74.4454 -0.115932 -0.636766 -0.394591 -0.652216 +VERTEX_SE3:QUAT 2382 43.3518 56.223 -75.444 -0.0590093 -0.657594 -0.351939 -0.663496 +VERTEX_SE3:QUAT 2383 43.3962 56.7397 -76.4903 0.00519776 -0.667984 -0.289052 -0.685725 +VERTEX_SE3:QUAT 2384 43.3907 56.8956 -77.4953 0.0455682 -0.672863 -0.253756 -0.693388 +VERTEX_SE3:QUAT 2385 43.3034 57.3244 -78.5854 0.0754456 -0.677117 -0.224716 -0.696652 +VERTEX_SE3:QUAT 2386 43.4479 57.6074 -79.7569 0.0982104 -0.681015 -0.194969 -0.698971 +VERTEX_SE3:QUAT 2387 43.4767 57.5466 -80.897 0.137305 -0.682255 -0.156251 -0.7009 +VERTEX_SE3:QUAT 2388 43.6949 57.4618 -82.024 0.17872 -0.694165 -0.113869 -0.687916 +VERTEX_SE3:QUAT 2389 43.8563 57.25 -83.3381 0.230241 -0.690239 -0.0607384 -0.683278 +VERTEX_SE3:QUAT 2390 43.9604 56.82 -84.3401 0.259748 -0.68936 -0.0338722 -0.675401 +VERTEX_SE3:QUAT 2391 43.9716 56.3064 -85.3035 0.29021 -0.685446 0.00202003 -0.667785 +VERTEX_SE3:QUAT 2392 44.0075 55.7882 -86.2951 0.310124 -0.687099 0.0123385 -0.656937 +VERTEX_SE3:QUAT 2393 44.1458 55.1979 -87.118 0.326161 -0.683773 0.0468581 -0.651059 +VERTEX_SE3:QUAT 2394 44.2211 54.5622 -87.9544 0.375356 -0.662739 0.0948687 -0.641003 +VERTEX_SE3:QUAT 2395 44.3025 53.87 -88.7461 0.433292 -0.629837 0.143915 -0.628372 +VERTEX_SE3:QUAT 2396 44.5046 52.9093 -89.2943 0.449747 -0.618026 0.171157 -0.621672 +VERTEX_SE3:QUAT 2397 44.8643 52.1111 -89.8345 0.488025 -0.586748 0.219888 -0.607624 +VERTEX_SE3:QUAT 2398 45.1356 51.4365 -90.3489 0.506253 -0.566947 0.258263 -0.596305 +VERTEX_SE3:QUAT 2399 45.4809 50.4149 -90.8373 0.54251 -0.539009 0.298598 -0.570957 +VERTEX_SE3:QUAT 2400 45.8363 49.228 -91.0378 0.575899 -0.505745 0.339918 -0.544994 +VERTEX_SE3:QUAT 2401 46.0801 48.2515 -91.2475 0.612747 -0.455485 0.391492 -0.513623 +VERTEX_SE3:QUAT 2402 46.3561 47.3731 -91.0953 0.644953 -0.408898 0.445178 -0.467605 +VERTEX_SE3:QUAT 2403 46.5095 46.4722 -90.7966 0.660255 -0.373877 0.476003 -0.444635 +VERTEX_SE3:QUAT 2404 46.6988 45.6293 -90.3424 0.68155 -0.331713 0.515342 -0.399848 +VERTEX_SE3:QUAT 2405 46.8786 44.7965 -89.8796 0.683902 -0.307247 0.533134 -0.391976 +VERTEX_SE3:QUAT 2406 47.0626 43.8386 -89.2613 0.6932 -0.271288 0.55897 -0.365281 +VERTEX_SE3:QUAT 2407 47.2743 43.2194 -88.661 0.69609 -0.248853 0.580781 -0.340918 +VERTEX_SE3:QUAT 2408 47.4086 42.7874 -87.9849 0.712628 -0.201142 0.603981 -0.294806 +VERTEX_SE3:QUAT 2409 47.4966 42.3693 -87.1059 0.713729 -0.150691 0.635211 -0.253753 +VERTEX_SE3:QUAT 2410 47.5728 42.0506 -86.2893 0.71099 -0.134678 0.645418 -0.244523 +VERTEX_SE3:QUAT 2411 47.7197 41.5902 -85.4462 0.71089 -0.0945306 0.666356 -0.204129 +VERTEX_SE3:QUAT 2412 47.7651 41.3763 -84.5447 0.703386 -0.0197484 0.69505 -0.147525 +VERTEX_SE3:QUAT 2413 47.5992 41.2414 -83.8346 0.695016 -0.0087575 0.707503 -0.127733 +VERTEX_SE3:QUAT 2414 47.5756 41.0925 -82.7745 0.686404 0.0342601 0.721659 -0.0829658 +VERTEX_SE3:QUAT 2415 47.6163 41.2866 -81.987 0.675087 0.069671 0.73362 -0.0347011 +VERTEX_SE3:QUAT 2416 47.5096 41.4921 -81.192 0.661773 0.127638 0.738119 0.0307583 +VERTEX_SE3:QUAT 2417 47.3564 41.9068 -80.2762 0.645699 0.182175 0.736926 0.0826186 +VERTEX_SE3:QUAT 2418 47.2931 42.2411 -79.5699 0.633312 0.205375 0.738634 0.105625 +VERTEX_SE3:QUAT 2419 47.1374 42.5438 -78.7338 0.610371 0.261464 0.732107 0.152 +VERTEX_SE3:QUAT 2420 46.952 43.1409 -78.2617 0.584015 0.314796 0.719687 0.20465 +VERTEX_SE3:QUAT 2421 46.7268 43.8484 -77.6786 0.544735 0.371366 0.706715 0.25672 +VERTEX_SE3:QUAT 2422 46.4547 44.7963 -77.1725 0.521204 0.401315 0.700617 0.276459 +VERTEX_SE3:QUAT 2423 46.2725 45.5193 -76.84 0.499823 0.42833 0.689223 0.302789 +VERTEX_SE3:QUAT 2424 45.986 46.4406 -76.6984 0.471241 0.453062 0.675821 0.340488 +VERTEX_SE3:QUAT 2425 45.604 47.3943 -76.4476 0.422723 0.495066 0.642697 0.403925 +VERTEX_SE3:QUAT 2426 45.4197 48.2083 -76.4257 0.387736 0.516377 0.632708 0.42743 +VERTEX_SE3:QUAT 2427 45.1035 48.9009 -76.479 0.352055 0.530729 0.627967 0.44726 +VERTEX_SE3:QUAT 2428 44.8547 49.8279 -76.6837 0.3357 0.548853 0.617762 0.452147 +VERTEX_SE3:QUAT 2429 44.4816 50.653 -76.8527 0.316603 0.568247 0.59885 0.467158 +VERTEX_SE3:QUAT 2430 44.1784 51.4157 -77.1121 0.285308 0.592944 0.574655 0.486609 +VERTEX_SE3:QUAT 2431 44.0291 52.0388 -77.4006 0.238515 0.614051 0.536317 0.527652 +VERTEX_SE3:QUAT 2432 43.6524 52.6332 -77.8811 0.202952 0.629016 0.508441 0.55194 +VERTEX_SE3:QUAT 2433 43.3447 53.1672 -78.5151 0.165776 0.637109 0.486197 0.57465 +VERTEX_SE3:QUAT 2434 43.383 53.6102 -79.1715 0.109236 0.655188 0.432761 0.609519 +VERTEX_SE3:QUAT 2435 43.3675 54.11 -79.6946 0.0626141 0.664482 0.391771 0.633292 +VERTEX_SE3:QUAT 2436 43.3193 54.3609 -80.4725 -0.000266205 0.671883 0.333996 0.661075 +VERTEX_SE3:QUAT 2437 43.334 54.5542 -81.2129 -0.0392966 0.67361 0.295674 0.676227 +VERTEX_SE3:QUAT 2438 43.177 54.7075 -81.911 -0.0771595 0.677452 0.263153 0.682536 +VERTEX_SE3:QUAT 2439 43.2272 54.791 -82.853 -0.138411 0.674516 0.203876 0.69592 +VERTEX_SE3:QUAT 2440 43.2343 54.711 -83.5017 -0.197259 0.666769 0.141537 0.70461 +VERTEX_SE3:QUAT 2441 43.3245 54.3891 -84.2515 -0.227393 0.659622 0.102109 0.70906 +VERTEX_SE3:QUAT 2442 43.533 54.1666 -84.8312 -0.271656 0.648918 0.0551162 0.708569 +VERTEX_SE3:QUAT 2443 43.7725 53.9423 -85.4402 -0.30833 0.646662 0.00193926 0.69768 +VERTEX_SE3:QUAT 2444 43.9318 53.4433 -85.8933 -0.345477 0.632208 -0.0422218 0.692225 +VERTEX_SE3:QUAT 2445 44.2738 52.9316 -86.2512 -0.377627 0.623671 -0.0794315 0.679796 +VERTEX_SE3:QUAT 2446 44.611 52.542 -86.8564 -0.39871 0.603305 -0.109143 0.682013 +VERTEX_SE3:QUAT 2447 44.7473 51.9791 -87.2439 -0.46485 0.556998 -0.168155 0.667376 +VERTEX_SE3:QUAT 2448 45.0639 51.6272 -87.3253 -0.486278 0.532815 -0.200601 0.662873 +VERTEX_SE3:QUAT 2449 45.2318 51.0934 -87.7064 -0.531508 0.494455 -0.263411 0.635317 +VERTEX_SE3:QUAT 2450 45.3955 50.4036 -87.7386 -0.539529 0.485131 -0.283182 0.627188 +VERTEX_SE3:QUAT 2451 45.7078 49.8878 -87.8943 -0.566915 0.451079 -0.323639 0.608599 +VERTEX_SE3:QUAT 2452 45.9699 49.3683 -87.9437 -0.588663 0.40729 -0.369429 0.592547 +VERTEX_SE3:QUAT 2453 46.1881 48.8303 -87.9253 -0.595518 0.385254 -0.401051 0.579738 +VERTEX_SE3:QUAT 2454 46.3766 48.1471 -87.8115 -0.617239 0.355333 -0.427536 0.556747 +VERTEX_SE3:QUAT 2455 46.5302 47.8287 -87.6155 -0.636406 0.311902 -0.475373 0.521272 +VERTEX_SE3:QUAT 2456 46.7353 47.3343 -87.4193 -0.655714 0.254445 -0.521885 0.48263 +VERTEX_SE3:QUAT 2457 47.0123 46.8383 -87.2201 -0.665275 0.212469 -0.558269 0.447886 +VERTEX_SE3:QUAT 2458 47.0774 46.439 -86.9181 -0.675355 0.162877 -0.593248 0.406723 +VERTEX_SE3:QUAT 2459 47.2734 46.0812 -86.4942 -0.680709 0.104498 -0.625992 0.365855 +VERTEX_SE3:QUAT 2460 47.1074 46.0611 -85.9705 -0.680407 0.0727088 -0.646777 0.336808 +VERTEX_SE3:QUAT 2461 47.0826 45.9012 -85.4462 -0.671176 0.0456036 -0.676009 0.300757 +VERTEX_SE3:QUAT 2462 47.0773 45.6593 -84.9468 -0.669506 -0.0121206 -0.69966 0.249179 +VERTEX_SE3:QUAT 2463 46.898 45.5262 -84.3104 -0.660532 -0.0371735 -0.716555 0.221055 +VERTEX_SE3:QUAT 2464 46.8805 45.4786 -83.8172 -0.654668 -0.0791116 -0.728963 0.183752 +VERTEX_SE3:QUAT 2465 46.8316 45.7267 -83.3095 -0.648444 -0.122285 -0.739263 0.134376 +VERTEX_SE3:QUAT 2466 46.8348 45.7779 -82.6675 -0.641332 -0.150993 -0.745741 0.0988182 +VERTEX_SE3:QUAT 2467 46.8881 45.7435 -82.1211 -0.617348 -0.217649 -0.755541 0.0258537 +VERTEX_SE3:QUAT 2468 46.5283 46.0256 -81.8343 -0.605642 -0.247566 -0.756227 -0.00551225 +VERTEX_SE3:QUAT 2469 46.4756 46.1295 -81.3415 -0.576091 -0.297592 -0.758651 -0.0632976 +VERTEX_SE3:QUAT 2470 46.0765 46.4127 -81.1303 -0.54384 -0.345752 -0.754398 -0.124809 +VERTEX_SE3:QUAT 2471 46.0185 46.7899 -80.9362 -0.500558 -0.404626 -0.742005 -0.187479 +VERTEX_SE3:QUAT 2472 45.7942 47.0628 -80.7377 -0.467099 -0.437203 -0.731441 -0.235938 +VERTEX_SE3:QUAT 2473 45.8572 47.4787 -80.4563 -0.439306 -0.469037 -0.715217 -0.274733 +VERTEX_SE3:QUAT 2474 45.6523 47.8496 -80.5886 -0.41813 -0.494296 -0.695359 -0.311952 +VERTEX_SE3:QUAT 2475 45.3939 48.3766 -80.7115 -0.39348 -0.514284 -0.679781 -0.344359 +VERTEX_SE3:QUAT 2476 45.1258 48.739 -80.5778 -0.374617 -0.53251 -0.671151 -0.354472 +VERTEX_SE3:QUAT 2477 44.9109 48.967 -80.5823 -0.327543 -0.560965 -0.640696 -0.409318 +VERTEX_SE3:QUAT 2478 44.6876 49.3616 -80.575 -0.287821 -0.584231 -0.61357 -0.446502 +VERTEX_SE3:QUAT 2479 44.5731 49.9713 -80.7501 -0.246814 -0.609366 -0.574635 -0.487392 +VERTEX_SE3:QUAT 2480 44.3677 50.2595 -81.0865 -0.209248 -0.626611 -0.547648 -0.513474 +VERTEX_SE3:QUAT 2481 44.1676 50.5708 -81.4603 -0.176459 -0.635612 -0.523866 -0.538911 +VERTEX_SE3:QUAT 2482 44.0374 50.7651 -81.7982 -0.144885 -0.639464 -0.496771 -0.568606 +VERTEX_SE3:QUAT 2483 43.9545 51.1228 -82.0224 -0.118725 -0.646567 -0.464737 -0.593191 +VERTEX_SE3:QUAT 2484 43.9828 51.3102 -82.3699 -0.0805805 -0.657576 -0.431981 -0.611958 +VERTEX_SE3:QUAT 2485 44.0012 51.6298 -82.636 -0.0367508 -0.662719 -0.389667 -0.638445 +VERTEX_SE3:QUAT 2486 44.1127 51.746 -82.7912 0.0328154 -0.663837 -0.318808 -0.675725 +VERTEX_SE3:QUAT 2487 44.2101 51.5567 -83.198 0.0468281 -0.668355 -0.290649 -0.683104 +VERTEX_SE3:QUAT 2488 44.21 51.6052 -83.5124 0.0961788 -0.671731 -0.235778 -0.695655 +VERTEX_SE3:QUAT 2489 44.139 51.5099 -83.9523 0.141639 -0.66973 -0.18903 -0.704036 +VERTEX_SE3:QUAT 2490 44.2719 51.4012 -84.3375 0.167 -0.670204 -0.16115 -0.704959 +VERTEX_SE3:QUAT 2491 44.2296 51.3461 -84.6946 0.225943 -0.664472 -0.0862561 -0.707097 +VERTEX_SE3:QUAT 2492 44.363 51.1878 -84.822 0.259799 -0.647002 -0.0406764 -0.715708 +VERTEX_SE3:QUAT 2493 44.3511 50.9698 -85.0695 0.284659 -0.637398 -0.0183964 -0.715789 +VERTEX_SE3:QUAT 2494 44.2467 50.8798 -85.3684 0.331246 -0.617359 0.0266288 -0.713047 +VERTEX_SE3:QUAT 2495 44.2482 50.6422 -85.7676 0.372263 -0.600805 0.0682867 -0.704124 +VERTEX_SE3:QUAT 2496 44.3116 50.2138 -85.9661 0.39847 -0.581719 0.0960083 -0.702571 +VERTEX_SE3:QUAT 2497 44.2675 49.8961 -86.1857 0.428402 -0.557016 0.142983 -0.696965 +VERTEX_SE3:QUAT 2498 44.3157 49.597 -86.1301 0.449415 -0.537947 0.180115 -0.690071 +VERTEX_SE3:QUAT 2499 44.4728 49.3803 -86.238 0.487649 -0.504993 0.228516 -0.674508 +EDGE_SE3:QUAT 0 1 0.341895 -0.0416997 0.0330394 -0.00189341 0.00395691 0.0899835 0.995934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.021 0.00193512 2.06612 399.993 0.496977 99.203 +EDGE_SE3:QUAT 1 2 0.229005 0.138346 -0.0985239 -0.00129613 0.00838261 0.0556547 0.998414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.092 0.00603324 4.22391 399.972 0.295462 99.7404 +EDGE_SE3:QUAT 2 3 0.134845 -0.100952 -0.235999 -0.00104098 -0.00250309 0.0603806 0.998172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.007 0.000887159 -1.2098 399.997 0.342813 99.6399 +EDGE_SE3:QUAT 3 4 0.160394 0.0789167 -0.144281 0.00366694 0.000256785 0.0766428 0.997052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.995 -0.00011226 -0.0405833 399.996 -1.10509 99.4166 +EDGE_SE3:QUAT 4 5 0.325826 -0.0659292 -0.0839178 -0.0081336 0.00362712 0.0849512 0.996345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 -0.00115756 2.21543 399.974 2.38071 99.3106 +EDGE_SE3:QUAT 5 6 0.204328 -0.0241672 -0.0128254 -0.00460482 0.00328126 0.0315264 0.999487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.007 -0.000973884 1.72628 399.989 1.36091 99.9151 +EDGE_SE3:QUAT 6 7 0.259333 -0.220076 -0.122115 0.00553654 0.00952047 0.0754131 0.997092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.09 0.0158536 4.48687 399.957 -1.80642 99.4987 +EDGE_SE3:QUAT 7 8 0.330423 -0.218479 0.184829 -0.00182447 0.00407674 0.0599016 0.998194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.022 0.0011055 2.09741 399.992 0.498634 99.6543 +EDGE_SE3:QUAT 8 9 0.279749 -0.0817312 -0.0311683 0.00643391 0.00104029 0.0403555 0.999164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.984 0.000375753 0.363666 399.987 -1.93906 99.85 +EDGE_SE3:QUAT 9 10 0.439651 -0.036304 -0.0979001 -0.00905001 -0.00555868 0.0765773 0.997007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.994 0.00690182 -2.34962 399.965 2.80296 99.4554 +EDGE_SE3:QUAT 10 11 0.448391 0.0194033 -0.0588868 -0.00254441 0.000975 0.0667449 0.997766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.999 -0.00017308 0.587291 399.998 0.750806 99.5573 +EDGE_SE3:QUAT 11 12 0.601774 -0.00596884 -0.0316864 0.00675118 0.000245002 0.0745787 0.997192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.982 -0.000503439 -0.179649 399.986 -2.03083 99.4576 +EDGE_SE3:QUAT 12 13 0.0850905 -0.0358214 0.0945044 0.000639884 -0.00199952 0.0478191 0.998854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.005 0.00022276 -1.01606 399.998 -0.17287 99.7743 +EDGE_SE3:QUAT 13 14 0.406341 -0.0979121 0.0146315 -0.00374393 0.00460766 0.0425239 0.999078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.025 -9.85119e-05 2.39572 399.987 1.0842 99.8391 +EDGE_SE3:QUAT 14 15 0.34657 0.120479 -0.0772302 0.00613351 -0.00643779 0.0664602 0.997749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.048 0.00118553 -3.45083 399.971 -1.75525 99.6016 +EDGE_SE3:QUAT 15 16 0.456464 -0.230793 0.0240143 -0.00659229 0.00316439 0.0787036 0.996871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 -0.00080875 1.88408 399.982 1.92947 99.4027 +EDGE_SE3:QUAT 16 17 0.514306 -0.0150626 -0.0145896 -0.00401975 0.00212606 0.113676 0.993507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.003 0.000169078 1.32369 399.993 1.15944 98.717 +EDGE_SE3:QUAT 17 18 0.534286 0.253572 0.100366 -0.00283653 0.0115156 0.074389 0.997159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.175 0.0149326 5.85834 399.945 0.679473 99.544 +EDGE_SE3:QUAT 18 19 0.345823 0.105393 0.0308981 0.000422084 0.00419377 0.0140892 0.999892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.023 0.000621151 2.09307 399.993 -0.138441 99.9925 +EDGE_SE3:QUAT 19 20 0.46807 -0.0543662 0.0352444 -0.00196191 0.00569591 0.034257 0.999395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.042 0.000904515 2.88559 399.986 0.549583 99.9069 +EDGE_SE3:QUAT 20 21 0.569866 0.153941 0.181648 0.00192189 0.0132127 0.0296673 0.999471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.222 0.0117614 6.57083 399.93 -0.654694 100.034 +EDGE_SE3:QUAT 21 22 0.48147 -0.165285 -0.024962 0.00132192 0.0108198 0.0341163 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.149 0.00853762 5.37934 399.953 -0.470338 99.9654 +EDGE_SE3:QUAT 22 23 0.457005 -0.154486 0.111581 -0.00359739 0.0067025 0.0796605 0.996793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.059 0.00437718 3.50429 399.978 0.97281 99.4028 +EDGE_SE3:QUAT 23 24 0.460068 0.0012191 -0.000311304 0.00752137 0.00667671 0.0773615 0.996952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.021 0.00916006 2.97211 399.967 -2.36224 99.445 +EDGE_SE3:QUAT 24 25 0.505705 -0.0457969 0.0571836 0.00202826 0.00280132 0.092867 0.995673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.007 0.00159809 1.27713 399.996 -0.661795 99.1436 +EDGE_SE3:QUAT 25 26 0.396066 -0.0147835 0.0752318 0.00190251 0.00168042 0.0558766 0.998434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 0.000523388 0.774138 399.998 -0.589881 99.6906 +EDGE_SE3:QUAT 26 27 0.554342 -0.082874 0.0195301 -0.000463824 0.00516656 0.0717897 0.997406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.035 0.00322752 2.59149 399.989 0.0647183 99.5034 +EDGE_SE3:QUAT 27 28 0.405677 -0.0164516 -0.14359 0.00367028 0.0104746 0.0828534 0.9965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.123 0.0187916 5.02451 399.955 -1.27658 99.3898 +EDGE_SE3:QUAT 28 29 0.366064 0.109363 0.0995936 -0.00618271 0.00635643 0.0450251 0.998946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.043 -0.000691054 3.33977 399.972 1.79788 99.8391 +EDGE_SE3:QUAT 29 30 0.447825 -0.0626529 -0.073141 0.002345 0.00148424 0.0810386 0.996707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 0.00049219 0.623964 399.998 -0.728464 99.3461 +EDGE_SE3:QUAT 30 31 0.446624 -0.149658 0.0423714 0.00326231 0.0104361 0.0731404 0.997262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.126 0.0167671 5.05172 399.955 -1.13258 99.5409 +EDGE_SE3:QUAT 31 32 0.327353 -0.0599871 0.00611897 0.00900913 0.00452981 0.0602371 0.998133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.986 0.00476329 1.93222 399.968 -2.7589 99.6731 +EDGE_SE3:QUAT 32 33 0.709329 -0.188287 0.0378529 -0.00202672 0.0112525 0.0836101 0.996433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.167 0.017131 5.69489 399.949 0.419355 99.3921 +EDGE_SE3:QUAT 33 34 0.428707 0.162405 0.00594776 -0.00613741 0.000908824 0.0728462 0.997324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.988 -0.000850944 0.720008 399.988 1.82947 99.4819 +EDGE_SE3:QUAT 34 35 0.356338 0.033284 -0.199599 -0.0075939 0.00574001 0.0925712 0.995661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.034 0.0015584 3.26886 399.968 2.17393 99.1882 +EDGE_SE3:QUAT 35 36 0.521019 -0.0505509 -0.164282 -0.00724726 0.00979356 0.0784293 0.996845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.122 0.00725028 5.2119 399.945 2.0214 99.474 +EDGE_SE3:QUAT 36 37 0.329602 0.0156168 0.0525484 0.00274797 0.0065892 0.099141 0.995048 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.046 0.00860071 3.10292 399.982 -0.957498 99.0472 +EDGE_SE3:QUAT 37 38 0.366813 -0.0752683 -0.115229 0.00104291 0.0100846 0.0338846 0.999374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.13 0.00719446 5.01766 399.959 -0.381187 99.9562 +EDGE_SE3:QUAT 38 39 0.618377 0.0578938 0.103393 0.00692039 0.00226925 0.0662669 0.997775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.984 0.00130012 0.855348 399.984 -2.10776 99.5777 +EDGE_SE3:QUAT 39 40 0.636906 0.157098 -0.0500064 -0.00825985 0.00817142 0.0401534 0.999126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.069 -0.00205729 4.27957 399.952 2.41242 99.9092 +EDGE_SE3:QUAT 40 41 0.55055 0.0364808 -0.0365541 0.00448827 0.00980289 0.0458109 0.998892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.109 0.0117656 4.77028 399.957 -1.43653 99.8608 +EDGE_SE3:QUAT 41 42 0.660865 0.171451 -0.110704 -0.00536445 0.00843784 0.075445 0.9971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.092 0.00565971 4.44087 399.962 1.4826 99.493 +EDGE_SE3:QUAT 42 43 0.502157 0.166008 -0.0195176 -0.00195722 0.00654815 0.047578 0.998844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.056 0.0024559 3.32375 399.982 0.524905 99.8054 +EDGE_SE3:QUAT 43 44 0.494995 0.0325404 -0.0791926 -0.0006 0.0130851 0.00822665 0.99988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.223 0.00174845 6.54903 399.931 0.158442 100.113 +EDGE_SE3:QUAT 44 45 0.357421 -0.179353 -0.253832 -0.00182294 0.0167314 0.0556438 0.998309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.366 0.0251936 8.41153 399.888 0.360686 99.8885 +EDGE_SE3:QUAT 45 46 0.549017 -0.0323211 0.0437218 -0.010342 0.00665683 0.0498159 0.998683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.027 -0.00329585 3.63024 399.949 3.03687 99.8191 +EDGE_SE3:QUAT 46 47 0.59857 -0.0825892 -0.0750772 -0.00128276 0.00333259 0.0786547 0.996896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.015 0.00121008 1.71751 399.995 0.332466 99.3899 +EDGE_SE3:QUAT 47 48 0.634876 -0.0183952 0.0245626 -0.00283385 0.00627831 0.0751296 0.99715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.052 0.00378698 3.25119 399.982 0.756035 99.4669 +EDGE_SE3:QUAT 48 49 0.542938 -0.115345 0.00522098 0.00266354 0.0147337 0.0797473 0.996703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.263 0.0337273 7.20254 399.915 -1.03535 99.5129 +EDGE_SE3:QUAT 49 50 0.786233 0.0643949 -0.139267 0.00186434 0.00874745 0.0890463 0.995987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.091 0.0131772 4.2442 399.97 -0.716803 99.2593 +EDGE_SE3:QUAT 50 51 0.670888 -0.239288 0.144786 0.00606759 0.00146794 0.0490176 0.998778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.987 0.000642818 0.554054 399.988 -1.83539 99.7718 +EDGE_SE3:QUAT 51 52 0.988066 -0.119053 0.079414 -0.00407774 0.00743239 0.0552613 0.998436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.071 0.00262282 3.84181 399.973 1.14142 99.7401 +EDGE_SE3:QUAT 52 53 0.550309 0.112491 -0.159187 -0.00112846 0.00662109 0.0178716 0.999818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.057 0.000666393 3.32221 399.982 0.314859 99.9993 +EDGE_SE3:QUAT 53 54 0.638918 0.0661151 0.0442451 0.00346748 0.00277606 0.0381663 0.999262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.004 0.00134462 1.30686 399.993 -1.06169 99.8629 +EDGE_SE3:QUAT 54 55 0.62477 -0.00411993 -0.0479437 -9.32402e-05 0.0107652 0.0512936 0.998626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.15 0.01057 5.3749 399.954 -0.0825864 99.8178 +EDGE_SE3:QUAT 55 56 0.765626 -0.0632934 -0.14521 0.00045896 0.00631419 0.0616818 0.998076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.051 0.00464402 3.12975 399.984 -0.215912 99.6471 +EDGE_SE3:QUAT 56 57 0.780791 0.0445135 0.076528 0.00697625 0.01192 0.0287993 0.99949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.156 0.0151632 5.83747 399.93 -2.16099 100.028 +EDGE_SE3:QUAT 57 58 0.677334 0.0523832 -0.129781 0.00308223 0.00470903 0.0384551 0.999244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.023 0.00282625 2.28044 399.989 -0.961104 99.8698 +EDGE_SE3:QUAT 58 59 0.770904 0.00617635 -0.0745303 0.000740565 0.0134348 0.0612567 0.998031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.23 0.0206439 6.67165 399.929 -0.387043 99.7498 +EDGE_SE3:QUAT 59 60 0.774808 -0.135367 -0.0248524 -0.00208684 0.00159357 0.0792081 0.996855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 4.42979e-05 0.891267 399.998 0.601286 99.376 +EDGE_SE3:QUAT 60 61 0.479333 -0.0126589 -0.102246 0.00656265 0.00306973 0.0910869 0.995817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.989 0.00215953 1.1657 399.984 -2.02777 99.1879 +EDGE_SE3:QUAT 61 62 0.797582 0.0438476 0.0310194 0.000563401 0.0141122 0.0748158 0.997097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.253 0.0272214 7.00004 399.923 -0.380905 99.5778 +EDGE_SE3:QUAT 62 63 0.742007 0.107876 -0.103637 0.00123169 0.00364153 0.0927349 0.995683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.015 0.00245318 1.73841 399.995 -0.438124 99.1491 +EDGE_SE3:QUAT 63 64 0.689769 0.199185 0.0815092 0.00194911 0.0108837 0.0954061 0.995377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.142 0.0213535 5.28801 399.954 -0.794705 99.1702 +EDGE_SE3:QUAT 64 65 0.925214 0.170788 -0.0242523 0.000236692 0.00165307 0.0472913 0.99888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.003 0.000266901 0.818169 399.999 -0.086703 99.7783 +EDGE_SE3:QUAT 65 66 0.706086 0.26849 -0.0748405 -0.00123609 0.005965 0.0585188 0.998268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.047 0.00307295 3.01705 399.985 0.300983 99.6833 +EDGE_SE3:QUAT 66 67 0.638484 -0.0754865 -0.0200711 0.000702168 0.0119339 0.0488902 0.998733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.182 0.0132508 5.93645 399.944 -0.327417 99.86 +EDGE_SE3:QUAT 67 68 0.856711 0.0944398 0.0924844 0.00798668 0.0106753 0.0810501 0.996621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.096 0.0218207 4.91976 399.939 -2.5719 99.4333 +EDGE_SE3:QUAT 68 69 0.833231 0.0810845 -0.168993 -0.00597791 0.0124887 0.0606618 0.998062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.203 0.0101072 6.44466 399.926 1.64195 99.7568 +EDGE_SE3:QUAT 69 70 0.657439 -0.0980627 -0.177485 -0.00324111 0.00688941 0.0351991 0.999351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.06 0.000802309 3.50987 399.978 0.923879 99.9134 +EDGE_SE3:QUAT 70 71 0.706164 -0.049235 -0.0823152 0.00147578 0.00118093 0.0409766 0.999158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.001 0.000247651 0.553311 399.999 -0.45255 99.8336 +EDGE_SE3:QUAT 71 72 0.747846 -0.0790405 0.0165401 -0.00145374 -0.00852997 0.0804944 0.996718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.089 0.0113278 -4.17105 399.972 0.5746 99.4019 +EDGE_SE3:QUAT 72 73 0.920407 -0.0152539 0.117976 0.00500087 0.00610607 0.0725683 0.997332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.03 0.0069034 2.82142 399.979 -1.59047 99.5042 +EDGE_SE3:QUAT 73 74 0.517825 0.0136797 -0.0438358 0.00489588 -0.00274557 0.0338741 0.99941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 -0.000984627 -1.47085 399.99 -1.45037 99.8983 +EDGE_SE3:QUAT 74 75 0.830853 -0.144022 -0.147814 -0.000132684 0.0137286 0.0782581 0.996839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.241 0.026171 6.8371 399.927 -0.175844 99.5184 +EDGE_SE3:QUAT 75 76 0.75027 -0.0799915 -0.0511733 -0.00237825 0.0123054 0.0580514 0.998235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.199 0.0131341 6.22015 399.938 0.570534 99.7722 +EDGE_SE3:QUAT 76 77 0.906628 0.0631322 0.137461 -0.00404764 0.0204325 0.067123 0.997527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.55 0.0430451 10.3531 399.83 0.9399 99.8515 +EDGE_SE3:QUAT 77 78 0.727647 -0.028039 0.00313257 -0.00613666 0.00495602 0.0158995 0.999842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.019 -0.00243012 2.53614 399.979 1.82516 100.004 +EDGE_SE3:QUAT 78 79 0.732052 -0.0104581 -0.178661 -0.000347412 0.0129845 0.0654092 0.997774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.218 0.01935 6.48465 399.934 -0.0659639 99.6898 +EDGE_SE3:QUAT 79 80 0.866 0.115588 -0.170978 0.00942081 0.0111956 0.078865 0.996778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.096 0.0242879 5.12286 399.928 -3.00571 99.482 +EDGE_SE3:QUAT 80 81 0.918307 0.211437 -0.0455169 0.00501673 0.00558181 0.0107229 0.999914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.029 0.00333783 2.75857 399.98 -1.51688 100.018 +EDGE_SE3:QUAT 81 82 0.660276 -0.0939153 0.0456885 -0.00568324 0.00701885 0.0740189 0.997216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.061 0.00292847 3.74475 399.97 1.60185 99.4996 +EDGE_SE3:QUAT 82 83 0.808712 0.0158234 0.0759911 0.00749883 0.0132962 0.0510205 0.998581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.188 0.0246137 6.40633 399.915 -2.38538 99.8739 +EDGE_SE3:QUAT 83 84 0.977589 -0.0806277 -0.0165069 0.00115446 -0.00477683 0.0186502 0.999814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.029 0.00021643 -2.40078 399.99 -0.328519 99.9817 +EDGE_SE3:QUAT 84 85 0.931384 -0.0211719 0.045156 0.00345677 0.00707621 0.0463977 0.998892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.056 0.00629989 3.4356 399.977 -1.10304 99.8219 +EDGE_SE3:QUAT 85 86 0.847935 0.105966 -0.0790951 0.00184922 0.00428146 0.0700504 0.997533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.02 0.00288539 2.05379 399.992 -0.615454 99.5224 +EDGE_SE3:QUAT 86 87 0.816373 -0.0484386 0.0967984 0.00250058 0.00957189 0.0583702 0.998246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.111 0.011583 4.68517 399.963 -0.862428 99.7233 +EDGE_SE3:QUAT 87 88 1.09479 0.103914 -0.166369 0.00220566 0.0156623 0.0694096 0.997463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.304 0.0332011 7.71171 399.904 -0.879636 99.6873 +EDGE_SE3:QUAT 88 89 0.951079 0.0478632 0.079033 -0.000686104 0.0134619 0.0743388 0.997142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.234 0.0233207 6.7323 399.929 0.00514066 99.5741 +EDGE_SE3:QUAT 89 90 0.898548 0.0121024 -0.0233981 -0.00475836 0.0128568 0.0408805 0.99907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.214 0.0062089 6.53923 399.927 1.32222 99.9581 +EDGE_SE3:QUAT 90 91 0.986115 0.0617607 -0.07348 0.00748443 0.00964577 0.0690114 0.997541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.08 0.0166078 4.49372 399.949 -2.3802 99.5994 +EDGE_SE3:QUAT 91 92 1.19151 -0.125735 -0.140539 0.00826411 0.00628408 0.0577189 0.998279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.013 0.00782868 2.84684 399.965 -2.55306 99.7114 +EDGE_SE3:QUAT 92 93 0.969192 0.137519 -0.0466096 -0.00162451 0.00846079 0.0304654 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.093 0.0025778 4.25762 399.971 0.435789 99.9585 +EDGE_SE3:QUAT 93 94 0.935602 -0.0420428 -0.278862 0.00160017 0.0119624 0.0714055 0.997374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.178 0.019754 5.88811 399.944 -0.651693 99.5886 +EDGE_SE3:QUAT 94 95 0.933126 0.0691404 -0.0493149 0.00626432 0.0113415 0.0442614 0.998936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.14 0.0164603 5.49652 399.938 -1.97974 99.9019 +EDGE_SE3:QUAT 95 96 0.980764 0.00375579 -0.101989 -0.00850298 0.010257 0.0896364 0.995885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.134 0.00959439 5.54976 399.935 2.36834 99.3006 +EDGE_SE3:QUAT 96 97 1.12489 -0.0646296 0.0312703 0.00689334 0.0131774 0.0828278 0.996453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.176 0.0315443 6.20906 399.921 -2.28885 99.4397 +EDGE_SE3:QUAT 97 98 0.92336 0.12824 -0.110114 -0.00316458 -0.00252256 0.0342895 0.999404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.003 0.00108511 -1.19488 399.995 0.966861 99.8896 +EDGE_SE3:QUAT 98 99 0.978164 0.0557018 0.0139987 0.00583382 0.00870469 0.0275345 0.999566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.08 0.00850352 4.25394 399.96 -1.79795 99.9857 +EDGE_SE3:QUAT 99 100 1.02609 0.0363458 -0.0675104 -0.000779949 0.0036414 0.0481585 0.998833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.017 0.000881624 1.83951 399.995 0.198918 99.7777 +EDGE_SE3:QUAT 100 101 1.13013 0.028431 -0.203878 0.00969196 -0.000706688 0.0607891 0.998103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.965 -0.00162746 -0.705199 399.971 -2.90059 99.6598 +EDGE_SE3:QUAT 101 102 0.969271 -0.00770857 0.0840952 0.00893695 0.0147985 0.047763 0.998709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.229 0.030146 7.13244 399.892 -2.82194 99.9412 +EDGE_SE3:QUAT 102 103 1.04189 0.021552 -0.101847 0.000546377 6.85255e-05 0.0649692 0.997887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 -4.73869e-08 0.012864 400 -0.164921 99.578 +EDGE_SE3:QUAT 103 104 1.03192 0.122897 0.253434 -0.00591342 0.0206086 0.0681951 0.997442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.562 0.0412615 10.519 399.82 1.49266 99.8509 +EDGE_SE3:QUAT 104 105 1.08911 0.113631 -0.230208 0.00211022 0.00472326 0.0244791 0.999687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.026 0.00193411 2.32953 399.99 -0.656223 99.9567 +EDGE_SE3:QUAT 105 106 1.03026 0.175845 -0.148347 -0.00449687 0.012759 0.0376615 0.999199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.211 0.00541979 6.47668 399.928 1.25277 99.9806 +EDGE_SE3:QUAT 106 107 1.02205 0.0709188 -0.0572234 -0.00381587 0.0118922 0.0622894 0.99798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.186 0.0117325 6.07089 399.939 0.996629 99.7182 +EDGE_SE3:QUAT 107 108 0.980173 0.0959369 -0.0752456 -0.00203378 0.00951588 0.0357575 0.999313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.118 0.00394627 4.79762 399.962 0.542065 99.9375 +EDGE_SE3:QUAT 108 109 1.05095 -0.0257689 -0.023528 0.00431153 -0.000530344 0.0706724 0.99749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.994 -0.000396716 -0.446496 399.994 -1.28697 99.5066 +EDGE_SE3:QUAT 109 110 1.20359 -0.0647622 -0.0597841 -0.0047966 0.00500172 0.0710026 0.997452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.029 0.000941846 2.69376 399.983 1.3687 99.5222 +EDGE_SE3:QUAT 110 111 0.95796 0.131102 -0.0761098 0.00265172 0.0107278 0.026072 0.999599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.144 0.00814083 5.32119 399.952 -0.851273 100.014 +EDGE_SE3:QUAT 111 112 1.05014 -0.0223277 -0.233038 -0.00209511 0.0164148 0.0903114 0.995776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.352 0.0408479 8.26827 399.894 0.331094 99.3756 +EDGE_SE3:QUAT 112 113 1.11301 -0.131397 -0.0723134 0.0033051 0.0111757 0.0571932 0.998295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.149 0.0159042 5.46026 399.948 -1.11982 99.7606 +EDGE_SE3:QUAT 113 114 1.147 -0.0327704 0.0305984 0.00706444 0.00815849 0.0488287 0.998749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.056 0.0105806 3.86426 399.96 -2.1996 99.8197 +EDGE_SE3:QUAT 114 115 1.1207 -0.0117095 -0.223917 -0.00422855 0.0105591 0.0978301 0.995138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.15 0.0162352 5.48382 399.951 1.06191 99.1304 +EDGE_SE3:QUAT 115 116 1.07318 -0.0107915 -0.191525 -0.00580249 0.0161359 0.0769412 0.996888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.346 0.0280187 8.30029 399.886 1.49236 99.6074 +EDGE_SE3:QUAT 116 117 1.19468 -0.159599 -0.0241275 -0.00267924 0.015108 0.0523216 0.998512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.299 0.0177104 7.62562 399.907 0.645622 99.8901 +EDGE_SE3:QUAT 117 118 1.18149 0.0809769 0.0817434 0.0058403 0.0104489 0.0429216 0.999007 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.118 0.0138026 5.06706 399.948 -1.84189 99.8991 +EDGE_SE3:QUAT 118 119 1.27252 0.0408358 -0.0858404 -0.00190865 0.00869288 0.0591419 0.99821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.099 0.00652777 4.4016 399.969 0.469738 99.7051 +EDGE_SE3:QUAT 119 120 1.19134 0.0228141 0.0131211 -0.00258343 0.0180633 0.112271 0.99351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.426 0.0621732 9.11311 399.874 0.367013 98.9715 +EDGE_SE3:QUAT 120 121 1.24715 0.0802271 0.0691544 0.000833734 0.012447 0.0592323 0.998166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.197 0.017327 6.17753 399.939 -0.39785 99.7565 +EDGE_SE3:QUAT 121 122 1.30121 -0.0106717 0.100456 0.00851854 0.00463139 0.0315193 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.994 0.004553 2.15256 399.97 -2.58499 99.936 +EDGE_SE3:QUAT 122 123 1.17626 0.120445 0.0833338 0.00335007 0.0107091 0.0577336 0.998269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.136 0.0148599 5.22444 399.952 -1.12919 99.7475 +EDGE_SE3:QUAT 123 124 1.44683 0.08159 0.130293 -0.0043153 0.00492198 0.0715215 0.997418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.029 0.00114751 2.63476 399.984 1.22484 99.5127 +EDGE_SE3:QUAT 124 125 1.15683 0.0142598 -0.0920316 -0.000871625 0.00873889 0.045793 0.998912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.1 0.00556885 4.38631 399.969 0.181405 99.8442 +EDGE_SE3:QUAT 125 126 1.14944 -0.152584 -0.0639707 -0.00444429 0.00686253 0.0651731 0.99784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.06 0.00270223 3.59231 399.975 1.24427 99.6163 +EDGE_SE3:QUAT 126 127 1.31421 -0.0301921 0.0136282 0.0127549 0.0119701 0.0208214 0.99963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.11 0.0197688 5.82519 399.895 -3.8749 100.102 +EDGE_SE3:QUAT 127 128 1.1777 -0.0441652 -0.0328759 0.00188926 0.0143701 0.0648087 0.997792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.258 0.0261849 7.08939 399.919 -0.753451 99.7226 +EDGE_SE3:QUAT 128 129 1.25589 -0.0832053 0.0755096 0.00968511 0.0208769 0.0174635 0.999583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.516 0.0336868 10.3485 399.799 -2.97496 100.299 +EDGE_SE3:QUAT 129 130 1.22503 0.0665453 0.0105143 -0.00301251 0.0144171 0.041699 0.999022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.272 0.0114218 7.278 399.914 0.783422 99.9762 +EDGE_SE3:QUAT 130 131 1.38719 0.0506626 -0.103822 -0.00204912 0.0157733 0.0474977 0.998745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.325 0.0182077 7.93599 399.9 0.464894 99.9511 +EDGE_SE3:QUAT 131 132 1.14129 0.0525289 0.0422534 -0.00339603 0.00786245 0.0929538 0.995634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.083 0.00824565 4.09049 399.972 0.872768 99.1851 +EDGE_SE3:QUAT 132 133 1.36611 0.0933038 0.0101952 0.00581418 0.00246534 0.0192083 0.999796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.993 0.00149309 1.16524 399.988 -1.75378 99.9772 +EDGE_SE3:QUAT 133 134 1.39693 0.0169225 0.0380645 0.00129542 0.0105104 0.0839802 0.996411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.136 0.0174768 5.15861 399.957 -0.566509 99.3703 +EDGE_SE3:QUAT 134 135 1.23352 0.143751 -0.0425504 0.00312912 0.00704217 0.0800988 0.996757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.053 0.00857646 3.35116 399.978 -1.05309 99.3937 +EDGE_SE3:QUAT 135 136 1.41106 -0.0532619 -0.0108934 -0.00101628 0.00714484 0.084329 0.996412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.067 0.00712346 3.60152 399.98 0.183919 99.3252 +EDGE_SE3:QUAT 136 137 1.15381 0.177075 0.0374688 0.00513289 0.0134228 0.0635085 0.997878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.206 0.0259815 6.49524 399.923 -1.71104 99.7248 +EDGE_SE3:QUAT 137 138 1.42676 -0.0517682 -0.164318 -0.00167798 0.0163679 0.0247573 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.349 0.00922069 8.21209 399.892 0.422296 100.128 +EDGE_SE3:QUAT 138 139 1.26672 0.0397922 -0.0564532 0.0014312 0.0184108 0.100785 0.994737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.418 0.0621468 9.04509 399.872 -0.803047 99.2152 +EDGE_SE3:QUAT 139 140 1.44915 -0.0475323 0.092421 0.000907604 0.0158326 0.0607934 0.998024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.319 0.0285271 7.86362 399.902 -0.464881 99.8041 +EDGE_SE3:QUAT 140 141 1.33591 -0.214487 0.010121 0.0025861 0.00868468 0.0636542 0.997931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.089 0.0103959 4.22887 399.969 -0.887117 99.6476 +EDGE_SE3:QUAT 141 142 1.35222 0.0658626 0.0313342 -0.00477341 0.0196473 0.0646971 0.9977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.509 0.0364948 9.98559 399.84 1.17762 99.8642 +EDGE_SE3:QUAT 142 143 1.48539 0.0659756 0.0937671 0.00860125 0.0167899 0.0544629 0.998338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.306 0.0396207 8.09825 399.87 -2.76267 99.9128 +EDGE_SE3:QUAT 143 144 1.47044 -0.0991464 -0.018496 0.00562863 0.0184569 0.0414093 0.998956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.413 0.0349047 9.08444 399.857 -1.84012 100.071 +EDGE_SE3:QUAT 144 145 1.45225 -0.0303321 0.0124329 -0.00327086 0.0178566 0.0879825 0.995957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.42 0.045654 9.04871 399.872 0.666401 99.4558 +EDGE_SE3:QUAT 145 146 1.39071 -0.210258 -0.0390088 0.00386635 0.0122614 0.0816589 0.996577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.172 0.0251555 5.90758 399.939 -1.36199 99.4372 +EDGE_SE3:QUAT 146 147 1.57347 0.0979423 0.0218775 -0.00280335 0.00938187 0.106355 0.99428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.118 0.0149413 4.82301 399.963 0.640775 98.935 +EDGE_SE3:QUAT 147 148 1.27099 -0.0250882 0.0109643 0.00591107 0.0165955 0.0767979 0.996891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.312 0.0448461 7.98836 399.885 -2.02946 99.6029 +EDGE_SE3:QUAT 148 149 1.40051 0.10627 -0.101023 0.00382101 0.0146294 0.0703524 0.997408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.255 0.0312456 7.1259 399.914 -1.35298 99.6535 +EDGE_SE3:QUAT 149 150 1.53584 0.259858 -0.067094 0.00311081 0.0119761 0.0903375 0.995834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.167 0.0254066 5.77843 399.943 -1.15195 99.2819 +EDGE_SE3:QUAT 150 151 1.50343 0.0900941 -0.0232025 -0.00270013 0.0169159 0.0606942 0.998009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.376 0.027086 8.53684 399.884 0.604627 99.8364 +EDGE_SE3:QUAT 151 152 1.54611 0.27024 -0.0573247 0.000480027 0.024595 0.0445546 0.998704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.781 0.0496041 12.2885 399.761 -0.361725 100.224 +EDGE_SE3:QUAT 152 153 1.40938 -0.0190962 0.0406198 0.00347019 0.0111607 0.0238775 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.154 0.0090968 5.53006 399.947 -1.09407 100.033 +EDGE_SE3:QUAT 153 154 1.40071 -0.0348716 0.0796097 0.00852713 0.0203489 0.0520194 0.998402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.474 0.0536572 9.89613 399.818 -2.76791 100.029 +EDGE_SE3:QUAT 154 155 1.37532 0.0303392 0.00973663 0.000900381 0.0162546 0.0495901 0.998637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.338 0.0248455 8.08989 399.896 -0.431113 99.9378 +EDGE_SE3:QUAT 155 156 1.22703 0.0210456 -0.0498942 0.00634674 0.0166869 0.0580291 0.998155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.321 0.0377788 8.10431 399.881 -2.09746 99.8621 +EDGE_SE3:QUAT 156 157 1.31766 -0.118396 -0.0643189 0.00430906 0.00936659 0.0261583 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.103 0.00796982 4.61407 399.96 -1.34156 99.9972 +EDGE_SE3:QUAT 157 158 1.4538 0.111238 0.022365 0.00210573 0.0207182 0.0849186 0.99617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.533 0.0680828 10.1993 399.835 -0.984352 99.573 +EDGE_SE3:QUAT 158 159 1.47945 0.0548181 -0.117826 -0.00258969 0.0177555 0.0826612 0.996416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.413 0.0429529 8.96137 399.875 0.482844 99.5416 +EDGE_SE3:QUAT 159 160 1.38283 0.0324891 0.255533 0.00451967 0.0165661 0.0605892 0.998015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.329 0.0360131 8.0986 399.888 -1.55663 99.8247 +EDGE_SE3:QUAT 160 161 1.39937 0.0949158 0.03063 0.00370709 0.0199032 0.0640513 0.997741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.487 0.0515557 9.78523 399.842 -1.36657 99.864 +EDGE_SE3:QUAT 161 162 1.32635 0.00237235 -0.158713 -0.00222918 0.0161695 0.0410677 0.999023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.342 0.0158602 8.13492 399.894 0.535924 100.017 +EDGE_SE3:QUAT 162 163 1.43595 -0.0666765 -0.0226963 -0.000837195 0.0228282 0.0993689 0.994788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.666 0.0907388 11.3828 399.801 -0.203893 99.3743 +EDGE_SE3:QUAT 163 164 1.37631 0.125108 0.101829 0.00945681 0.0156885 0.0457831 0.998783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.258 0.0331489 7.57503 399.878 -2.97981 99.981 +EDGE_SE3:QUAT 164 165 1.47347 -0.0114871 0.0244473 0.0006253 0.0148313 0.0522502 0.998524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.282 0.0214478 7.38343 399.913 -0.342547 99.8799 +EDGE_SE3:QUAT 165 166 1.39015 -0.0627038 -0.100217 0.00072373 0.0167181 0.043203 0.998926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.36 0.0228253 8.33429 399.889 -0.36124 100.008 +EDGE_SE3:QUAT 166 167 1.42634 -0.0434544 -0.0641663 -0.00315859 0.00842642 0.0466423 0.998871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.092 0.00341351 4.29438 399.968 0.86904 99.8365 +EDGE_SE3:QUAT 167 168 1.46179 -0.000134202 -0.235566 -0.00138878 0.00945416 0.0742203 0.997196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.117 0.0107835 4.7669 399.964 0.275972 99.5129 +EDGE_SE3:QUAT 168 169 1.50116 -0.0630477 0.110722 -0.00136756 0.0223696 0.0665851 0.997529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.65 0.0570843 11.2143 399.803 0.112783 99.9079 +EDGE_SE3:QUAT 169 170 1.56377 0.144771 0.103893 -0.00508346 0.0175107 0.0443741 0.998849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.401 0.0159155 8.88481 399.869 1.36925 100.03 +EDGE_SE3:QUAT 170 171 1.5639 0.00334451 -0.0976223 -0.00329574 0.0160205 0.0501764 0.998606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.337 0.0182065 8.09868 399.894 0.82786 99.9337 +EDGE_SE3:QUAT 171 172 1.68862 -0.0586818 -0.0303397 -0.00471031 0.0161342 0.0419942 0.998976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.34 0.0123202 8.18049 399.889 1.27728 100.016 +EDGE_SE3:QUAT 172 173 1.58131 0.00755403 -0.0452305 0.000964126 0.0100744 0.0737287 0.997227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.127 0.0141093 4.97165 399.96 -0.438598 99.5262 +EDGE_SE3:QUAT 173 174 1.72212 0.0594114 -0.167495 0.000377957 0.0185118 0.0718223 0.997246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.438 0.0445662 9.20747 399.867 -0.379509 99.7216 +EDGE_SE3:QUAT 174 175 1.59936 -0.0663353 0.0552965 1.22662e-05 0.00681948 0.0719981 0.997381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.06 0.00598458 3.39385 399.982 -0.102331 99.5139 +EDGE_SE3:QUAT 175 176 1.72026 0.0330118 -0.0506746 0.00368107 0.0169043 0.0829467 0.996404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.341 0.0466165 8.2244 399.887 -1.38621 99.5078 +EDGE_SE3:QUAT 176 177 1.60182 0.0883911 0.132384 0.00418187 0.0171113 0.0386218 0.999099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.362 0.0270046 8.45548 399.88 -1.38585 100.057 +EDGE_SE3:QUAT 177 178 1.692 0.0275745 0.0436645 -0.00513075 0.00792932 0.0859723 0.996253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.082 0.0063141 4.20332 399.967 1.40358 99.3165 +EDGE_SE3:QUAT 178 179 1.4636 0.277218 0.00306782 0.000345921 0.01455 0.0607737 0.998045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.271 0.0234749 7.24348 399.917 -0.28081 99.7777 +EDGE_SE3:QUAT 179 180 1.85634 -0.0585747 0.0483485 0.00573932 0.0152982 0.0896545 0.995839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.257 0.0428174 7.29072 399.903 -1.9989 99.3587 +EDGE_SE3:QUAT 180 181 1.64267 -0.0179925 0.00251776 0.00326882 0.0210598 0.0498232 0.998531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.557 0.045904 10.4242 399.823 -1.18918 100.06 +EDGE_SE3:QUAT 181 182 1.80108 0.00341645 0.1077 -0.00129814 0.0168266 0.0463998 0.99878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.369 0.0215609 8.44151 399.887 0.233395 99.9841 +EDGE_SE3:QUAT 182 183 1.68527 0.061889 -0.183727 -0.000560794 0.0170123 0.0727924 0.997202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.373 0.0368808 8.49857 399.887 -0.0797953 99.672 +EDGE_SE3:QUAT 183 184 1.51155 0.149797 0.0264479 -0.0047195 0.0201 0.0508607 0.998492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.531 0.0280264 10.1852 399.832 1.2111 100.036 +EDGE_SE3:QUAT 184 185 1.68482 0.0347309 -0.0284604 0.00059401 0.0239939 0.0544364 0.998229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.741 0.0575731 11.9693 399.773 -0.438104 100.105 +EDGE_SE3:QUAT 185 186 1.76482 -0.0323671 0.069191 -4.1816e-05 0.0113373 0.0876933 0.996083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.164 0.0200165 5.63409 399.951 -0.187488 99.3199 +EDGE_SE3:QUAT 186 187 1.50619 0.2211 -0.0934862 0.00925609 0.0200522 0.0719611 0.997163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.434 0.065537 9.59122 399.823 -3.06528 99.7716 +EDGE_SE3:QUAT 187 188 1.77122 -0.15748 0.0888511 0.00600839 0.0235543 0.0114601 0.999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.702 0.0257607 11.7566 399.768 -1.85364 100.385 +EDGE_SE3:QUAT 188 189 1.59992 0.0430631 -0.0982293 0.00147451 0.0199033 0.0506021 0.998519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.506 0.038654 9.89735 399.844 -0.643035 100.019 +EDGE_SE3:QUAT 189 190 1.77684 -0.12741 -0.065838 0.00227695 0.017931 0.037222 0.999144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.409 0.0253922 8.91324 399.871 -0.81582 100.086 +EDGE_SE3:QUAT 190 191 1.81203 0.0301962 0.0214748 -0.0020841 0.0162436 0.0405069 0.999045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.345 0.0159788 8.16805 399.893 0.49363 100.023 +EDGE_SE3:QUAT 191 192 1.72204 -0.00873939 -0.125301 -0.00182818 0.0138844 0.0615441 0.998006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.252 0.0190312 6.99072 399.923 0.377418 99.7583 +EDGE_SE3:QUAT 192 193 1.62744 0.000274444 0.135329 0.0060713 0.0184382 0.0485268 0.998633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.405 0.0395526 9.03263 399.857 -1.99921 100.006 +EDGE_SE3:QUAT 193 194 1.82308 0.0310364 0.155292 -0.00137301 0.0225458 0.0492742 0.99853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.662 0.0421405 11.309 399.798 0.190296 100.115 +EDGE_SE3:QUAT 194 195 1.5502 0.0689414 -0.120656 0.00935928 0.0214078 0.0701257 0.997265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.504 0.0727406 10.2768 399.8 -3.1071 99.8366 +EDGE_SE3:QUAT 195 196 1.78057 0.146144 0.0610981 -0.00615888 0.0206031 0.044099 0.998796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.555 0.0214138 10.4622 399.818 1.66519 100.12 +EDGE_SE3:QUAT 196 197 1.65409 -0.196292 0.0459151 0.000848481 0.00979166 0.0504685 0.998677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.122 0.00942001 4.86052 399.962 -0.353557 99.8119 +EDGE_SE3:QUAT 197 198 1.69503 0.195056 -0.169086 0.00567755 0.0103218 0.055363 0.998397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.113 0.0153877 4.95971 399.95 -1.81818 99.7736 +EDGE_SE3:QUAT 198 199 1.76688 0.097001 -0.0593896 0.00312211 0.0222108 0.0781457 0.99669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.608 0.0740857 10.9158 399.808 -1.2836 99.7281 +EDGE_SE3:QUAT 199 200 1.90254 0.325562 -0.0777571 -0.0039361 0.0184251 0.0423695 0.998924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.444 0.0189004 9.3089 399.86 1.02445 100.066 +EDGE_SE3:QUAT 200 201 1.68051 -0.033179 -0.0389823 0.00128621 0.0144123 0.0723439 0.997275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.261 0.0283042 7.12142 399.919 -0.595077 99.6197 +EDGE_SE3:QUAT 201 202 1.86513 0.254449 0.00888724 0.0103693 0.0233277 0.0879194 0.9958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.576 0.100658 11.0535 399.766 -3.52162 99.6111 +EDGE_SE3:QUAT 202 203 1.82231 -0.109072 -0.163625 -0.001534 0.0201417 0.0964417 0.995134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.524 0.0674656 10.0893 399.843 0.0703674 99.354 +EDGE_SE3:QUAT 203 204 1.92344 0.0251315 0.120875 0.00313423 0.0239 0.0345754 0.999111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.728 0.0427977 11.8953 399.771 -1.10338 100.28 +EDGE_SE3:QUAT 204 205 1.62506 0.111677 -0.0497328 -0.000602767 0.0181963 0.0743303 0.997067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.427 0.0430989 9.09018 399.871 -0.0899988 99.6784 +EDGE_SE3:QUAT 205 206 1.96882 0.0238452 0.0993766 0.00799698 0.0120549 0.0553556 0.998362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.143 0.0222372 5.74766 399.926 -2.53309 99.8078 +EDGE_SE3:QUAT 206 207 2.00298 0.01153 -0.045501 0.00377517 0.0180958 0.0588017 0.998099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.402 0.040323 8.8962 399.869 -1.34498 99.8819 +EDGE_SE3:QUAT 207 208 1.66844 0.0318303 -0.13248 -0.000891617 0.0253582 0.0765571 0.996742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.83 0.0862379 12.6814 399.749 -0.120001 99.8628 +EDGE_SE3:QUAT 208 209 1.78938 0.194344 0.0187949 0.00565062 0.0104829 0.0358437 0.999286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.122 0.0124946 5.11558 399.948 -1.77022 99.9554 +EDGE_SE3:QUAT 209 210 1.75655 -0.145987 -0.138479 0.00294806 0.0159014 0.0735655 0.997159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.308 0.0368265 7.78847 399.9 -1.11917 99.6329 +EDGE_SE3:QUAT 210 211 1.74459 -0.0573695 -0.00494877 0.00247032 0.0173214 0.0732826 0.997158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.371 0.042612 8.51882 399.883 -0.995506 99.6694 +EDGE_SE3:QUAT 211 212 1.83911 0.0396383 0.138066 -0.000405804 0.0158122 0.0398637 0.99908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.325 0.0173069 7.9114 399.901 -0.00415958 100.016 +EDGE_SE3:QUAT 212 213 2.02525 0.0376045 -0.121723 -0.000289703 0.0216972 0.0589898 0.998023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.608 0.049261 10.8426 399.815 -0.168456 99.9806 +EDGE_SE3:QUAT 213 214 1.8112 0.014488 0.0610334 0.00582348 0.0198361 0.0088023 0.999748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.495 0.017871 9.89979 399.833 -1.78007 100.277 +EDGE_SE3:QUAT 214 215 1.92421 0.0628544 -0.0421914 0.00882408 0.015862 0.0827586 0.996404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.25 0.0461978 7.44972 399.884 -2.91224 99.4993 +EDGE_SE3:QUAT 215 216 1.85809 0.12447 -0.126272 -0.00561629 0.0252406 0.073364 0.99697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.842 0.0717281 12.8354 399.739 1.31446 99.9266 +EDGE_SE3:QUAT 216 217 1.92819 0.131562 -0.0262865 -0.0101294 0.0233769 0.0545177 0.998188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.711 0.0310325 12.0119 399.749 2.78213 100.131 +EDGE_SE3:QUAT 217 218 2.09045 0.0502047 0.00895368 0.00453413 0.0159861 0.0820605 0.996489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.297 0.0424353 7.72791 399.897 -1.62426 99.5028 +EDGE_SE3:QUAT 218 219 1.66963 -0.0146119 0.0298604 -0.000488329 0.0159878 0.0856025 0.996201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.328 0.0384025 7.97326 399.901 -0.128244 99.4449 +EDGE_SE3:QUAT 219 220 1.94352 0.0237944 -0.0206842 -0.00392853 0.0190096 0.0661599 0.99762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.476 0.036339 9.63561 399.852 0.926903 99.8242 +EDGE_SE3:QUAT 220 221 2.08627 0.0695488 -0.0603994 0.0026963 0.0112843 0.0619176 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.154 0.0166167 5.52488 399.949 -0.949209 99.7052 +EDGE_SE3:QUAT 221 222 1.74306 0.123654 0.00155131 -0.00903106 0.0196514 0.0826388 0.996345 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.514 0.0424552 10.2269 399.821 2.38426 99.627 +EDGE_SE3:QUAT 222 223 1.85398 0.259788 0.0394136 0.00167243 0.0166439 0.0455052 0.998824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.353 0.0252001 8.26861 399.89 -0.652813 99.9857 +EDGE_SE3:QUAT 223 224 1.93641 0.262807 0.0398305 0.00397977 0.0152311 0.0945016 0.9954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.268 0.0426221 7.33453 399.909 -1.48468 99.2651 +EDGE_SE3:QUAT 224 225 1.73706 -0.0894922 -0.214004 -0.00642875 0.020807 0.103564 0.994384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.58 0.0707958 10.7184 399.819 1.4968 99.2545 +EDGE_SE3:QUAT 225 226 1.95821 0.0290485 -0.00119628 0.00133718 0.0203357 0.0530367 0.998385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.528 0.0418111 10.1139 399.837 -0.616107 100.006 +EDGE_SE3:QUAT 226 227 2.05299 0.0827588 -0.0318831 -0.00420984 0.0247151 0.0646904 0.99759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.803 0.0617185 12.5015 399.753 0.943362 100.02 +EDGE_SE3:QUAT 227 228 2.07201 0.0649026 -0.00477684 -0.000209626 0.0156355 0.0526691 0.99849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.316 0.0228043 7.81151 399.903 -0.101759 99.8933 +EDGE_SE3:QUAT 228 229 1.95294 0.039408 -0.0464725 -0.000507214 0.0204809 0.0654902 0.997643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.542 0.0483204 10.2357 399.835 -0.115841 99.8639 +EDGE_SE3:QUAT 229 230 2.03641 0.0722071 -0.0815322 -0.00172064 0.0223493 0.065766 0.997583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.65 0.0555617 11.2186 399.803 0.222598 99.9191 +EDGE_SE3:QUAT 230 231 1.8818 -0.11954 -0.0325278 2.20198e-05 0.0143602 0.0548093 0.998394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.266 0.0202934 7.16509 399.919 -0.164075 99.8433 +EDGE_SE3:QUAT 231 232 2.14098 -0.168831 0.0265906 -0.00821499 0.0127335 0.0534983 0.998453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.203 0.00551679 6.61762 399.914 2.3282 99.8539 +EDGE_SE3:QUAT 232 233 1.83433 0.0734373 0.0660469 -0.0060055 0.0244011 0.060753 0.997836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.785 0.0516477 12.4053 399.752 1.50478 100.068 +EDGE_SE3:QUAT 233 234 1.88659 0.110046 -0.107002 -0.00134342 0.0238304 0.0635643 0.997692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.738 0.0619463 11.9467 399.776 0.100789 99.9945 +EDGE_SE3:QUAT 234 235 2.26289 0.0870066 0.000505862 -0.00264206 0.0271489 0.0420359 0.998744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.964 0.0488757 13.6549 399.704 0.564938 100.345 +EDGE_SE3:QUAT 235 236 1.98665 -0.0129186 0.00442581 0.00195495 0.0282644 0.0792782 0.99645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.006 0.117497 13.9969 399.691 -1.03241 99.9221 +EDGE_SE3:QUAT 236 237 1.91157 0.183219 -0.0222053 0.00180706 0.0155097 0.031006 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.308 0.0161193 7.72091 399.904 -0.637856 100.072 +EDGE_SE3:QUAT 237 238 2.09429 -0.00379929 -0.134306 0.00253607 0.0208271 0.0898425 0.995735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.533 0.0729314 10.216 399.833 -1.1363 99.489 +EDGE_SE3:QUAT 238 239 1.77477 -0.0360535 -0.0690612 0.00252718 0.0166736 0.0844797 0.996282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.339 0.0448 8.16279 399.892 -1.04131 99.4764 +EDGE_SE3:QUAT 239 240 2.27011 0.219717 -0.00370011 -0.00301796 0.030069 0.0410216 0.998701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.183 0.0580087 15.1342 399.637 0.659398 100.472 +EDGE_SE3:QUAT 240 241 1.86571 -0.115437 0.00537699 0.000477654 0.018482 0.0223888 0.999578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.443 0.0146518 9.24141 399.864 -0.225618 100.189 +EDGE_SE3:QUAT 241 242 1.93868 0.0763127 -0.101444 -0.00145754 0.0171152 0.0456902 0.998808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.382 0.0217096 8.59033 399.883 0.280965 99.9978 +EDGE_SE3:QUAT 242 243 2.08485 0.0765796 0.0597433 -0.00421611 0.0214873 0.0812174 0.996456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.609 0.0598137 10.903 399.813 0.915548 99.6746 +EDGE_SE3:QUAT 243 244 2.24831 -0.0292934 0.0381868 0.00372641 0.0229039 0.0807128 0.996467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.641 0.0818576 11.2237 399.795 -1.48748 99.7083 +EDGE_SE3:QUAT 244 245 2.12642 -0.0938462 -0.262251 0.00142355 0.0172472 0.0334193 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.382 0.0202455 8.59518 399.881 -0.541795 100.096 +EDGE_SE3:QUAT 245 246 2.25275 -0.068501 -0.164155 0.0019045 0.0314772 0.0405969 0.998678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.275 0.0783314 15.7225 399.607 -0.822829 100.527 +EDGE_SE3:QUAT 246 247 2.02421 0.208041 0.0553142 0.00912654 0.016655 0.115791 0.993092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.254 0.0622315 7.60061 399.877 -3.13196 98.8543 +EDGE_SE3:QUAT 247 248 2.25098 0.199637 0.10075 0.00205736 0.0239465 0.0841695 0.996162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.716 0.0896806 11.8157 399.779 -1.02016 99.6852 +EDGE_SE3:QUAT 248 249 2.10342 0.107357 -0.15673 0.00320715 0.0266938 0.0666875 0.997412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.892 0.0923229 13.1966 399.72 -1.31561 100.048 +EDGE_SE3:QUAT 249 250 2.19817 0.218015 -0.00786808 0.00526525 0.0158396 0.0769106 0.996898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.287 0.0404852 7.6409 399.897 -1.82454 99.5833 +EDGE_SE3:QUAT 250 251 2.31288 -0.052153 -0.0731027 -0.0047604 0.0197553 0.058489 0.998081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.514 0.032417 10.0282 399.838 1.19682 99.9433 +EDGE_SE3:QUAT 251 252 2.18756 -0.0633361 -0.118089 0.000956977 0.0263208 0.0577488 0.997984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.888 0.0740911 13.1189 399.728 -0.589072 100.148 +EDGE_SE3:QUAT 252 253 2.08733 0.05078 -0.0744808 0.00308126 0.0138538 0.0434002 0.998957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.238 0.0188572 6.83931 399.922 -1.04442 99.9463 +EDGE_SE3:QUAT 253 254 2.09822 0.190315 -0.18488 -0.00145931 0.0244574 0.0690211 0.997314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.777 0.0709496 12.2622 399.765 0.10089 99.9434 +EDGE_SE3:QUAT 254 255 2.07268 0.043896 0.0290046 0.00564061 0.0234907 0.051958 0.998357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.676 0.063269 11.5619 399.775 -1.93375 100.117 +EDGE_SE3:QUAT 255 256 2.03781 -0.05167 0.123522 0.00611556 0.017599 0.0456572 0.998783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.368 0.0350521 8.62399 399.868 -1.99433 100.013 +EDGE_SE3:QUAT 256 257 2.45744 0.148313 -0.109088 -0.00350969 0.0196311 0.0734934 0.997096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.507 0.0449482 9.93603 399.844 0.764189 99.7373 +EDGE_SE3:QUAT 257 258 2.3833 -0.00345305 -0.128278 -0.00377585 0.0196329 0.0442098 0.998822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.505 0.0235635 9.91286 399.842 0.958965 100.082 +EDGE_SE3:QUAT 258 259 2.20419 0.199405 -0.00605771 -0.00326138 0.0206531 0.0560351 0.99821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.56 0.0367734 10.4227 399.827 0.746988 99.9912 +EDGE_SE3:QUAT 259 260 2.29002 0.135432 0.0287787 -0.00231936 0.0225032 0.0415617 0.99888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.662 0.0328634 11.3121 399.797 0.508986 100.186 +EDGE_SE3:QUAT 260 261 2.15078 -0.00596316 -0.135764 -0.00165046 0.0185738 0.0964935 0.995159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.447 0.0570975 9.31563 399.866 0.135288 99.3112 +EDGE_SE3:QUAT 261 262 2.20337 0.0580157 0.00134658 -0.000145345 0.0251238 0.082527 0.996272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.808 0.0927294 12.5191 399.756 -0.370568 99.7569 +EDGE_SE3:QUAT 262 263 2.03672 0.197414 -0.19402 0.0115839 0.0269312 0.071274 0.997026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.799 0.116364 12.9363 399.685 -3.85465 100.011 +EDGE_SE3:QUAT 263 264 2.1035 0.124143 0.0255684 0.00615253 0.0256559 0.0548582 0.998146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.804 0.0787219 12.6178 399.733 -2.12375 100.159 +EDGE_SE3:QUAT 264 265 2.30918 -0.100238 -0.145686 0.00311559 0.0127581 0.0530753 0.998504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.199 0.0189417 6.26705 399.934 -1.07028 99.8322 +EDGE_SE3:QUAT 265 266 2.21367 0.0949277 -0.155361 -0.00311254 0.0192197 0.074572 0.997026 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.486 0.0443467 9.71358 399.852 0.646907 99.7086 +EDGE_SE3:QUAT 266 267 2.13462 -0.146741 0.0671172 -0.00466665 0.02058 0.0642748 0.997709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.559 0.0403235 10.4474 399.825 1.13529 99.8957 +EDGE_SE3:QUAT 267 268 2.41615 0.05162 0.0750816 -0.00648909 0.0208437 0.0818254 0.996408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.578 0.0526328 10.694 399.815 1.6053 99.6576 +EDGE_SE3:QUAT 268 269 2.23469 0.0453752 -0.145289 0.00912995 0.0176887 0.0641063 0.997745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.333 0.0485545 8.4683 399.856 -2.96566 99.8196 +EDGE_SE3:QUAT 269 270 2.02699 0.121645 0.051122 -0.000170163 0.0100875 0.0746413 0.997159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.131 0.0134208 5.02785 399.96 -0.100149 99.5136 +EDGE_SE3:QUAT 270 271 2.27153 0.199102 0.161268 0.0044032 0.0254632 0.0468228 0.998569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.813 0.0649275 12.6101 399.74 -1.55636 100.233 +EDGE_SE3:QUAT 271 272 2.18299 -0.107375 0.0409429 0.00541026 0.0202106 0.0688115 0.99741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.486 0.0589374 9.85181 399.835 -1.90084 99.8104 +EDGE_SE3:QUAT 272 273 2.24056 0.080279 0.130438 0.00369951 0.0175468 0.0908683 0.995701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.365 0.0539596 8.51523 399.88 -1.43089 99.3842 +EDGE_SE3:QUAT 273 274 2.4215 0.195034 -0.155046 0.00202629 0.028604 0.0696601 0.997159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.036 0.106958 14.1941 399.681 -1.00348 100.081 +EDGE_SE3:QUAT 274 275 2.17327 0.134645 0.0613398 -0.00146112 0.0241753 0.0343844 0.999115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.762 0.032743 12.1298 399.766 0.272603 100.293 +EDGE_SE3:QUAT 275 276 2.35378 -0.0715283 -0.0653343 0.00513232 0.0277025 0.0610317 0.997738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.948 0.0962695 13.6514 399.694 -1.87395 100.16 +EDGE_SE3:QUAT 276 277 1.96311 0.155108 -0.0384223 -0.0117787 0.021777 0.0412882 0.99884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.597 0.00970767 11.1821 399.766 3.35103 100.216 +EDGE_SE3:QUAT 277 278 2.27018 0.14436 -0.136726 -0.00335692 0.0209014 0.0753301 0.996934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.574 0.0531077 10.5653 399.825 0.692047 99.7456 +EDGE_SE3:QUAT 278 279 2.34324 0.0231502 -0.114825 -0.00152021 0.0249085 0.074002 0.996946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.805 0.0790699 12.4873 399.757 0.088074 99.8876 +EDGE_SE3:QUAT 279 280 2.16599 0.0295354 -0.0855455 0.00379486 0.0207894 0.0507336 0.998489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.538 0.04644 10.2699 399.827 -1.34808 100.044 +EDGE_SE3:QUAT 280 281 2.25687 0.158581 0.223971 0.00466795 0.0172924 0.0711159 0.997307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.355 0.0442502 8.41586 399.879 -1.64686 99.7017 +EDGE_SE3:QUAT 281 282 2.46519 0.125342 -0.083333 -0.00233231 0.0176634 0.0462493 0.998771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.408 0.0220552 8.88919 399.874 0.536329 100.008 +EDGE_SE3:QUAT 282 283 2.47559 0.0556753 0.219299 -0.00117063 0.0197722 0.0753458 0.996961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.506 0.0507858 9.9019 399.847 0.0530496 99.7062 +EDGE_SE3:QUAT 283 284 2.39062 0.0988383 -0.0962819 -0.00768575 0.0307671 0.0540405 0.998035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.247 0.0696717 15.6452 399.604 1.97193 100.403 +EDGE_SE3:QUAT 284 285 2.35824 -0.0287721 -0.145039 0.00646342 0.0225101 0.0806798 0.996465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.59 0.0833696 10.8937 399.796 -2.30218 99.6991 +EDGE_SE3:QUAT 285 286 2.42832 0.0930126 -0.0489046 0.00451076 0.024002 0.0335148 0.99914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.727 0.0452165 11.9213 399.766 -1.51143 100.293 +EDGE_SE3:QUAT 286 287 2.44284 0.0404911 -0.136321 0.0124734 0.0236755 0.0274736 0.999264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.637 0.0561274 11.644 399.733 -3.86641 100.354 +EDGE_SE3:QUAT 287 288 2.41488 0.00870183 -0.20671 -0.00500904 0.0228259 0.0613937 0.99784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.687 0.0471259 11.5802 399.785 1.22227 100.002 +EDGE_SE3:QUAT 288 289 2.28864 -0.0381635 -0.0898246 -0.00254979 0.0319576 0.033852 0.998913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.335 0.0542739 16.0718 399.591 0.549398 100.607 +EDGE_SE3:QUAT 289 290 2.4637 0.0262221 -0.242672 0.00777782 0.020825 0.0428325 0.998835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.513 0.0481479 10.2094 399.813 -2.50933 100.129 +EDGE_SE3:QUAT 290 291 2.28355 -0.0154505 -0.0915172 -0.00324149 0.0209872 0.0406809 0.998946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.576 0.0256807 10.5735 399.821 0.801583 100.149 +EDGE_SE3:QUAT 291 292 2.58915 0.0339442 -0.0232328 -0.00251533 0.0186089 0.0484886 0.998647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.453 0.0257949 9.36937 399.86 0.574168 100.011 +EDGE_SE3:QUAT 292 293 2.42997 0.0755426 -0.0699184 -0.0044529 0.0215618 0.0510678 0.998452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.611 0.0336771 10.91 399.809 1.11543 100.076 +EDGE_SE3:QUAT 293 294 2.49862 0.00910517 0.00335106 0.0065694 0.0205657 0.0649429 0.997655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.496 0.0600916 10.0012 399.825 -2.23707 99.8752 +EDGE_SE3:QUAT 294 295 2.31422 0.0562027 -0.246499 -0.00298178 0.0278895 0.0331037 0.999058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.017 0.0381758 14.0286 399.687 0.709977 100.441 +EDGE_SE3:QUAT 295 296 2.46919 0.0840357 -0.067019 0.0070768 0.0278558 0.0459083 0.998532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.952 0.0822717 13.7414 399.681 -2.37355 100.336 +EDGE_SE3:QUAT 296 297 2.46877 0.0685008 -0.176631 -0.000877659 0.0249142 0.0812244 0.996384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.8 0.0883698 12.4525 399.759 -0.140977 99.7731 +EDGE_SE3:QUAT 297 298 2.49273 0.0234559 -0.0633944 0.00450294 0.030463 0.0763208 0.996608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.144 0.137499 14.9912 399.638 -1.81152 100.056 +EDGE_SE3:QUAT 298 299 2.44053 0.135077 0.0680864 0.00194423 0.0226542 0.0609516 0.997882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.65 0.0598888 11.2377 399.798 -0.858286 99.984 +EDGE_SE3:QUAT 299 300 2.75217 0.0228351 -0.220441 -3.4676e-05 0.0208962 0.0376903 0.999071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.566 0.0295458 10.4514 399.827 -0.146455 100.163 +EDGE_SE3:QUAT 300 301 2.4764 0.12383 -0.0145078 0.00467061 0.0267911 0.0347311 0.999027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.907 0.0570204 13.316 399.71 -1.58358 100.383 +EDGE_SE3:QUAT 301 302 2.5853 0.0742644 -0.153793 -0.000313448 0.0232885 0.0787162 0.996625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.696 0.0757022 11.6157 399.79 -0.27235 99.7574 +EDGE_SE3:QUAT 302 303 2.48018 0.167181 -0.0769526 -0.00527999 0.0307366 0.0666929 0.997286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.244 0.0988058 15.5703 399.618 1.17472 100.235 +EDGE_SE3:QUAT 303 304 2.43786 0.0831799 -0.240887 0.00163286 0.0288444 0.0967162 0.994893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.039 0.146246 14.2456 399.684 -1.047 99.6347 +EDGE_SE3:QUAT 304 305 2.6149 -0.0417122 -0.00826959 -0.00217183 0.0172964 0.0896475 0.995821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.391 0.0450401 8.71141 399.882 0.340531 99.4085 +EDGE_SE3:QUAT 305 306 2.65096 -0.0204622 -0.203166 0.00133705 0.0281265 0.051563 0.998273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.015 0.0768281 14.0263 399.688 -0.688387 100.285 +EDGE_SE3:QUAT 306 307 2.59701 0.0913949 -0.110267 -0.00998198 0.0202642 0.0653491 0.997607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.536 0.0296948 10.4998 399.804 2.72887 99.9047 +EDGE_SE3:QUAT 307 308 2.6107 0.171221 -0.172001 0.00755943 0.0236808 0.0394631 0.998912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.679 0.0565335 11.666 399.763 -2.45115 100.245 +EDGE_SE3:QUAT 308 309 2.58052 0.156052 -0.0282611 0.0117986 0.0314159 0.0513135 0.998119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.153 0.124195 15.3544 399.576 -3.85193 100.446 +EDGE_SE3:QUAT 309 310 2.54353 0.161132 -0.101395 0.000773394 0.0271682 0.073872 0.996897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.941 0.0993039 13.5172 399.713 -0.631615 99.9657 +EDGE_SE3:QUAT 310 311 2.52355 -0.0753586 -0.0144411 0.00336173 0.0324663 0.0208338 0.99925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.36 0.0508031 16.2439 399.577 -1.13942 100.697 +EDGE_SE3:QUAT 311 312 2.55843 0.191971 -0.117608 0.00915122 0.016898 0.0285495 0.999408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.321 0.0293127 8.29323 399.863 -2.83995 100.138 +EDGE_SE3:QUAT 312 313 2.59115 0.0146552 -0.0545087 0.00123164 0.0189927 0.0432727 0.998882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.463 0.0302411 9.46012 399.857 -0.533197 100.064 +EDGE_SE3:QUAT 313 314 2.7719 0.0842506 0.00799343 0.00120125 0.0296451 0.0430871 0.998631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.133 0.0716311 14.8117 399.652 -0.612739 100.428 +EDGE_SE3:QUAT 314 315 2.59943 0.08656 0.0773209 0.00372186 0.0309843 0.0647298 0.997415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.204 0.12141 15.3384 399.623 -1.51267 100.246 +EDGE_SE3:QUAT 315 316 2.56185 -0.038594 -0.130812 0.00567704 0.0299184 0.0555201 0.997993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.11 0.104455 14.7722 399.642 -2.02977 100.315 +EDGE_SE3:QUAT 316 317 2.58343 0.0497491 0.0273671 -0.00818394 0.0268731 0.046991 0.9985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.946 0.03978 13.6758 399.69 2.2008 100.317 +EDGE_SE3:QUAT 317 318 2.45417 -0.0622298 0.0542601 0.00125834 0.0251209 0.0751851 0.996852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.8 0.0873673 12.4665 399.755 -0.754132 99.8708 +EDGE_SE3:QUAT 318 319 2.5998 -0.0572395 -0.184706 0.0060738 0.0175298 0.0654486 0.997683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.356 0.0444772 8.50088 399.871 -2.05168 99.7882 +EDGE_SE3:QUAT 319 320 2.69845 0.0876705 -0.0726314 0.00544957 0.0235667 0.0335607 0.999144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.693 0.0459013 11.6833 399.772 -1.79017 100.28 +EDGE_SE3:QUAT 320 321 2.64474 -0.141128 -0.0760252 0.00365275 0.0156964 0.0839615 0.996339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.292 0.0408189 7.62066 399.903 -1.36111 99.4639 +EDGE_SE3:QUAT 321 322 2.53724 0.0399798 -0.0673388 0.000870617 0.0275224 0.0597601 0.997833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.972 0.0834058 13.7214 399.703 -0.587778 100.17 +EDGE_SE3:QUAT 322 323 2.64459 0.197896 0.086238 -0.0110957 0.0321071 0.0522296 0.998057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.352 0.0625072 16.4225 399.549 2.98956 100.508 +EDGE_SE3:QUAT 323 324 2.74405 0.118855 -0.128794 0.000232545 0.0299255 0.048681 0.998366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.158 0.0791475 14.9705 399.646 -0.358309 100.389 +EDGE_SE3:QUAT 324 325 2.79623 0.150104 -0.103291 0.000688999 0.0239158 0.0597622 0.997926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.734 0.0627758 11.9182 399.776 -0.491306 100.041 +EDGE_SE3:QUAT 325 326 2.58383 0.101972 0.0547001 -0.00175621 0.0349159 0.0357312 0.99875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.591 0.0725652 17.5505 399.514 0.279503 100.731 +EDGE_SE3:QUAT 326 327 2.73928 0.236487 -0.0642725 0.00295703 0.0085824 0.0926059 0.995661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.082 0.0136455 4.09513 399.97 -1.04838 99.1931 +EDGE_SE3:QUAT 327 328 2.5945 0.328433 -0.0731877 -3.21227e-05 0.0244605 0.0784596 0.996617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.766 0.0838292 12.189 399.768 -0.373622 99.7997 +EDGE_SE3:QUAT 328 329 2.71027 0.159758 -0.00752501 -0.00569161 0.0203181 0.0421052 0.99889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.539 0.0200591 10.3017 399.825 1.5357 100.127 +EDGE_SE3:QUAT 329 330 2.74073 0.181573 -0.0288775 0.00634123 0.0237532 0.0322002 0.999179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.699 0.047221 11.765 399.765 -2.05207 100.298 +EDGE_SE3:QUAT 330 331 2.80562 -0.00400767 -0.165928 0.00740226 0.0209152 0.0791025 0.99662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.494 0.0728084 10.0611 399.819 -2.55193 99.6797 +EDGE_SE3:QUAT 331 332 2.65997 -0.0256876 -0.0245655 0.0036443 0.0245859 0.0537575 0.998245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.758 0.0663596 12.1681 399.76 -1.35528 100.131 +EDGE_SE3:QUAT 332 333 2.61047 0.0522071 -0.053205 -0.00140785 0.0271271 0.073861 0.996899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.953 0.0941844 13.5941 399.712 0.0228809 99.97 +EDGE_SE3:QUAT 333 334 2.66212 0.106019 -0.0891965 -0.00511008 0.0315636 0.0459197 0.998433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.307 0.0668249 15.9489 399.595 1.24302 100.503 +EDGE_SE3:QUAT 334 335 2.86176 0.0803541 0.0339033 0.00476236 0.0190279 0.0375247 0.999103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.448 0.0329421 9.40597 399.851 -1.57012 100.115 +EDGE_SE3:QUAT 335 336 2.63173 0.0857922 -0.0765264 -0.0015998 0.0262688 0.0610581 0.997787 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.898 0.0719086 13.1807 399.727 0.160317 100.112 +EDGE_SE3:QUAT 336 337 2.63794 0.162968 -0.0143013 -6.09312e-05 0.0329113 0.0317573 0.998954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.409 0.0619243 16.5042 399.569 -0.188063 100.659 +EDGE_SE3:QUAT 337 338 2.86214 0.133707 0.0364661 -5.11627e-05 0.031355 0.0711723 0.996971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.264 0.125351 15.6611 399.617 -0.427611 100.178 +EDGE_SE3:QUAT 338 339 2.85028 0.00576298 -0.04141 0.00440868 0.029579 0.0710407 0.997025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.083 0.121959 14.5765 399.657 -1.73872 100.099 +EDGE_SE3:QUAT 339 340 2.71056 0.189705 -0.199337 -0.00178198 0.0333708 0.059233 0.997685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.449 0.113272 16.7612 399.56 0.142446 100.432 +EDGE_SE3:QUAT 340 341 2.73563 0.14105 -0.210063 0.00552618 0.0306617 0.0469912 0.998409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.177 0.0953185 15.1922 399.622 -1.94 100.436 +EDGE_SE3:QUAT 341 342 2.8134 0.160499 -0.0633969 -0.00149555 0.032982 0.055496 0.997913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.415 0.104118 16.5579 399.57 0.0856677 100.456 +EDGE_SE3:QUAT 342 343 2.9477 0.0578942 -0.185103 0.00856838 0.0242323 0.0288201 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.712 0.0505945 11.9817 399.746 -2.70584 100.343 +EDGE_SE3:QUAT 343 344 2.87939 0.28442 0.111384 -0.000350096 0.0183443 0.0553711 0.998297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.435 0.0328528 9.16921 399.867 -0.0978927 99.9285 +EDGE_SE3:QUAT 344 345 2.79356 0.136136 -0.163805 -0.0011788 0.0189645 0.0110048 0.999759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.468 0.00487623 9.50097 399.856 0.31178 100.241 +EDGE_SE3:QUAT 345 346 2.84246 0.109173 -0.141872 -0.00671827 0.0272135 0.0771332 0.996627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.982 0.0870599 13.8815 399.694 1.59551 99.9501 +EDGE_SE3:QUAT 346 347 2.84809 0.131258 -0.0112449 -0.00378753 0.0323968 0.0946942 0.994972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.37 0.168551 16.3427 399.59 0.524371 99.8476 +EDGE_SE3:QUAT 347 348 3.03374 0.123149 0.0392922 0.0118226 0.0277093 0.0445233 0.998554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.886 0.0913518 13.5461 399.66 -3.78612 100.363 +EDGE_SE3:QUAT 348 349 2.71507 0.0797169 -0.0195319 -0.000404419 0.0266515 0.0529286 0.998243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.92 0.0665991 13.3379 399.72 -0.15915 100.217 +EDGE_SE3:QUAT 349 350 2.82924 -0.026305 -0.0527465 -0.00687139 0.0238067 0.0550145 0.998178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.745 0.0407492 12.1222 399.759 1.79868 100.118 +EDGE_SE3:QUAT 350 351 2.87978 0.000666609 0.00867498 0.00216878 0.0273121 0.0291309 0.9992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.961 0.0450555 13.6428 399.702 -0.807242 100.437 +EDGE_SE3:QUAT 351 352 2.8458 0.130492 0.00630286 0.000258 0.0288438 0.0701125 0.997122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.067 0.105182 14.3883 399.676 -0.479436 100.087 +EDGE_SE3:QUAT 352 353 2.89921 0.207804 0.139018 -0.000643778 0.0240487 0.0687524 0.997344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.747 0.0699213 12.0238 399.774 -0.136764 99.9311 +EDGE_SE3:QUAT 353 354 3.03432 0.108421 -0.201936 -0.00036251 0.0312196 0.0274552 0.999135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.269 0.0471853 15.6585 399.611 -0.0608777 100.609 +EDGE_SE3:QUAT 354 355 2.83666 0.0997601 0.117516 0.00228988 0.0333715 0.0439432 0.998474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.43 0.0955839 16.66 399.559 -0.974937 100.584 +EDGE_SE3:QUAT 355 356 2.83688 -0.108716 -0.142772 -0.00620505 0.026741 0.0706053 0.997127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.946 0.0761801 13.6081 399.705 1.48377 100.025 +EDGE_SE3:QUAT 356 357 2.93553 0.148458 -0.31026 -1.51684e-05 0.024092 0.123979 0.991992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.724 0.126646 11.9035 399.785 -0.597687 98.8594 +EDGE_SE3:QUAT 357 358 2.86284 0.062805 -0.0995848 8.43661e-05 0.0369253 0.0801467 0.996099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.747 0.196128 18.4377 399.472 -0.61059 100.306 +EDGE_SE3:QUAT 358 359 2.82224 0.228264 -0.179339 0.00165748 0.0280487 0.0499604 0.998356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.008 0.0750125 13.9809 399.689 -0.774619 100.298 +EDGE_SE3:QUAT 359 360 2.87326 -0.0120272 0.0680689 -0.0029095 0.0237212 0.0620974 0.997784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.737 0.0565801 11.9515 399.775 0.578616 100.014 +EDGE_SE3:QUAT 360 361 2.94578 0.103857 -0.00621059 0.00531083 0.0244466 0.0527457 0.998295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.736 0.0681651 12.0483 399.758 -1.84834 100.139 +EDGE_SE3:QUAT 361 362 2.87397 0.145398 -0.125625 -0.0117815 0.0262376 0.0676463 0.997295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.906 0.0555498 13.5766 399.681 3.17733 100.089 +EDGE_SE3:QUAT 362 363 2.66867 0.067003 -0.117472 -0.00252688 0.0369347 0.0522139 0.997949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.782 0.119594 18.59 399.458 0.375956 100.69 +EDGE_SE3:QUAT 363 364 2.91263 -0.0694548 -0.160375 0.00133868 0.0416181 0.0559261 0.997566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.231 0.180075 20.8294 399.319 -0.856637 100.897 +EDGE_SE3:QUAT 364 365 2.91952 0.129288 -0.168713 0.00177207 0.0365411 0.0713938 0.996777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.7 0.176647 18.1932 399.48 -1.04587 100.416 +EDGE_SE3:QUAT 365 366 2.94564 0.101368 -0.0217288 0.00441321 0.0361804 0.0747153 0.996539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.631 0.188365 17.8789 399.49 -1.8558 100.345 +EDGE_SE3:QUAT 366 367 3.05253 0.227679 0.0875629 -0.00070043 0.0262976 0.0386144 0.998908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.899 0.0463214 13.1792 399.725 0.0082506 100.336 +EDGE_SE3:QUAT 367 368 2.90293 -0.113606 -0.0359419 0.000652966 0.0241392 0.0313656 0.999216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.755 0.0344801 12.071 399.768 -0.34607 100.309 +EDGE_SE3:QUAT 368 369 2.73985 0.213837 0.0781447 0.0127138 0.0297585 0.0762392 0.996564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.969 0.148653 14.2567 399.618 -4.2615 100.049 +EDGE_SE3:QUAT 369 370 2.96903 0.0841959 -0.012548 0.00234205 0.0262884 0.056361 0.998062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.878 0.0754414 13.0581 399.728 -0.996456 100.162 +EDGE_SE3:QUAT 370 371 3.04959 0.17682 0.0770593 0.00326326 0.0275839 0.0530357 0.998206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.962 0.0806853 13.6884 399.699 -1.26819 100.248 +EDGE_SE3:QUAT 371 372 2.87679 0.0868652 -0.348639 0.0028042 0.0374076 0.0594248 0.997528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.783 0.159231 18.6329 399.45 -1.27706 100.62 +EDGE_SE3:QUAT 372 373 3.15181 0.0931108 -0.130737 -8.54234e-05 0.029184 0.0595615 0.997798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.099 0.0909239 14.5914 399.665 -0.319469 100.24 +EDGE_SE3:QUAT 373 374 2.9804 0.0300695 -0.133022 0.00675166 0.0367689 0.0606653 0.997458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.673 0.169476 18.1585 399.462 -2.46027 100.572 +EDGE_SE3:QUAT 374 375 2.796 0.119305 -0.132021 0.00666993 0.0268353 0.042913 0.998696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.888 0.0723087 13.2551 399.704 -2.2267 100.324 +EDGE_SE3:QUAT 375 376 2.97303 0.0353721 -0.0658551 -0.00329821 0.0402461 0.0242548 0.99889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.119 0.0573428 20.2756 399.349 0.794308 101.087 +EDGE_SE3:QUAT 376 377 2.90809 0.096925 -0.0287028 0.00183123 0.0333852 0.0163116 0.999308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.447 0.0391751 16.7356 399.554 -0.655216 100.756 +EDGE_SE3:QUAT 377 378 2.86714 -0.140645 0.0190846 -0.00279306 0.0279486 0.0843079 0.996044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.018 0.11166 14.0645 399.694 0.367484 99.841 +EDGE_SE3:QUAT 378 379 2.98309 0.0224041 -0.0317134 0.00708742 0.0294332 0.0774711 0.996535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.032 0.135845 14.3472 399.655 -2.57794 99.9976 +EDGE_SE3:QUAT 379 380 3.07073 0.0327595 -0.0758744 -0.00240046 0.0277356 0.092973 0.995279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.998 0.122741 13.9309 399.702 0.204767 99.6767 +EDGE_SE3:QUAT 380 381 3.10564 0.0907773 0.0914588 0.00155415 0.0339852 0.0489594 0.998221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.486 0.106909 16.9777 399.544 -0.793717 100.566 +EDGE_SE3:QUAT 381 382 3.16325 0.0180853 -0.0669987 0.000553802 0.0320158 0.0324266 0.998961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.33 0.0617738 16.0391 399.592 -0.370828 100.613 +EDGE_SE3:QUAT 382 383 3.03272 -0.00647344 -0.0858751 -0.000484517 0.0259903 0.0273083 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.879 0.0320123 13.0251 399.731 0.00432032 100.399 +EDGE_SE3:QUAT 383 384 3.10634 0.144404 -0.304956 -0.00067108 0.0355631 0.0672745 0.9971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.635 0.150847 17.8141 399.505 -0.271983 100.432 +EDGE_SE3:QUAT 384 385 3.18203 0.08945 -0.147059 0.00428247 0.0331456 0.0455846 0.998401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.394 0.103715 16.486 399.562 -1.58027 100.559 +EDGE_SE3:QUAT 385 386 3.11767 0.0502868 -0.0732789 -0.0037998 0.0339499 0.0750747 0.996593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.509 0.144404 17.1294 399.544 0.632819 100.255 +EDGE_SE3:QUAT 386 387 3.01447 0.081949 -0.00580409 -0.00160062 0.0299102 0.073864 0.996818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.16 0.114445 14.9992 399.65 0.0404238 100.082 +EDGE_SE3:QUAT 387 388 3.20588 0.200952 -0.109076 0.0167509 0.0288964 0.0524379 0.998065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.877 0.120273 13.9179 399.596 -5.31801 100.362 +EDGE_SE3:QUAT 388 389 3.08185 -0.0043165 -0.198868 0.00157312 0.0350864 0.0265762 0.99903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.596 0.0647643 17.5821 399.509 -0.654173 100.793 +EDGE_SE3:QUAT 389 390 3.19034 -0.0125952 -0.105443 -0.00706966 0.0365683 0.0272695 0.998934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.747 0.0392781 18.4746 399.449 1.91784 100.888 +EDGE_SE3:QUAT 390 391 3.11216 0.162806 -0.267381 0.00464874 0.033497 0.0470968 0.998318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.419 0.109893 16.6467 399.553 -1.70299 100.561 +EDGE_SE3:QUAT 391 392 2.97079 0.13584 -0.1802 -0.00876545 0.0333759 0.0485033 0.998227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.464 0.0688845 16.9751 399.531 2.30339 100.585 +EDGE_SE3:QUAT 392 393 3.20136 0.202724 -0.0513181 0.00594374 0.0309479 0.0285882 0.999094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.212 0.0676798 15.4105 399.61 -1.95402 100.594 +EDGE_SE3:QUAT 393 394 3.30615 0.147441 -0.0178528 0.00258739 0.0347868 0.0480678 0.998235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.55 0.113398 17.3544 399.521 -1.10419 100.613 +EDGE_SE3:QUAT 394 395 3.10456 0.186036 -0.10306 0.00494051 0.0298057 0.0322036 0.999025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.127 0.0660608 14.8382 399.641 -1.66912 100.521 +EDGE_SE3:QUAT 395 396 3.02261 0.0745221 -0.211983 0.00580204 0.033 0.0726878 0.996792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.336 0.15733 16.2261 399.571 -2.21338 100.223 +EDGE_SE3:QUAT 396 397 3.18018 0.0461198 0.0624689 0.00819772 0.0335654 0.0427823 0.998487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.392 0.112994 16.6062 399.538 -2.73687 100.612 +EDGE_SE3:QUAT 397 398 3.07187 0.124298 0.0504869 0.00132454 0.0383708 0.0721189 0.996657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.88 0.195075 19.1341 399.427 -0.942175 100.502 +EDGE_SE3:QUAT 398 399 3.19152 0.0914991 -0.142671 -0.00314933 0.035051 0.0535976 0.997942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.607 0.108263 17.6577 399.51 0.571585 100.582 +EDGE_SE3:QUAT 399 400 3.21972 0.149408 -0.172255 -0.00480785 0.0297191 0.0566873 0.997938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.161 0.0768319 15.0272 399.642 1.10582 100.312 +EDGE_SE3:QUAT 400 401 3.27413 -0.024151 -0.182691 -0.000972076 0.0336683 0.0642593 0.997365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.469 0.12804 16.8754 399.555 -0.137119 100.381 +EDGE_SE3:QUAT 401 402 3.16193 0.214827 -0.189693 0.00125698 0.0247347 0.0627812 0.99772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.78 0.0715612 12.3018 399.76 -0.686148 100.03 +EDGE_SE3:QUAT 402 403 3.23378 -0.0293437 -0.0900133 0.0097408 0.0214663 0.0746784 0.996929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.498 0.0767381 10.2568 399.798 -3.24242 99.7725 +EDGE_SE3:QUAT 403 404 3.22247 -0.0128357 -0.141105 -0.00885321 0.0348051 0.060874 0.997499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.601 0.104063 17.7449 399.493 2.23088 100.522 +EDGE_SE3:QUAT 404 405 3.12734 0.0737837 -0.330096 -0.00312963 0.0433278 0.0616073 0.997155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.454 0.196131 21.8491 399.257 0.412325 100.948 +EDGE_SE3:QUAT 405 406 3.32 -0.0202808 -0.182474 -0.00301025 0.0305598 0.0718648 0.996942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.22 0.11257 15.3891 399.631 0.465618 100.144 +EDGE_SE3:QUAT 406 407 3.39081 0.0510789 0.0479507 0.00395488 0.0326827 0.0179983 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.377 0.0479793 16.3542 399.57 -1.2994 100.719 +EDGE_SE3:QUAT 407 408 3.26193 0.161083 -0.0500117 -0.000298992 0.036039 0.0296225 0.998911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.692 0.0684774 18.0926 399.483 -0.120663 100.825 +EDGE_SE3:QUAT 408 409 3.31422 0.155672 0.0320465 0.00323119 0.0208556 0.0289351 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.554 0.0292303 10.3792 399.824 -1.08856 100.222 +EDGE_SE3:QUAT 409 410 3.12657 0.253023 -0.0846193 0.00548389 0.0382597 0.0172974 0.999103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.884 0.0676447 19.1643 399.408 -1.76907 101.004 +EDGE_SE3:QUAT 410 411 3.37265 0.028787 -0.074283 0.00208951 0.0273213 0.0267965 0.999265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.963 0.0417675 13.6534 399.702 -0.770874 100.451 +EDGE_SE3:QUAT 411 412 3.4127 0.00462193 -0.204093 -0.00493317 0.0290731 0.0329247 0.999023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.105 0.0358559 14.6636 399.655 1.28752 100.497 +EDGE_SE3:QUAT 412 413 3.22292 0.103352 -0.0944368 -0.00327887 0.0466579 -0.00286171 0.998901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.841 -0.0278894 23.5016 399.126 1.00417 101.537 +EDGE_SE3:QUAT 413 414 3.26788 0.0146335 0.0374291 0.000321722 0.043179 0.0897627 0.995027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.377 0.300897 21.5518 399.285 -0.859163 100.488 +EDGE_SE3:QUAT 414 415 3.17238 0.0633887 -0.0437359 0.0072933 0.0331514 0.0624699 0.997469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.342 0.144105 16.3022 399.559 -2.59374 100.375 +EDGE_SE3:QUAT 415 416 3.30838 0.0944925 -0.0954845 0.00172188 0.0305561 0.0629519 0.997547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.19 0.110142 15.2069 399.634 -0.89737 100.252 +EDGE_SE3:QUAT 416 417 3.23944 0.0461074 -0.0681797 -1.09195e-05 0.0385602 0.0661024 0.997067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.917 0.176835 19.3035 399.418 -0.498953 100.601 +EDGE_SE3:QUAT 417 418 3.26348 0.127138 -0.1021 0.00320017 0.0280499 0.0635752 0.997578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.989 0.0974263 13.8885 399.691 -1.31341 100.14 +EDGE_SE3:QUAT 418 419 3.2143 0.22254 -0.0195218 0.00271952 0.0338279 0.0322151 0.998905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.474 0.075758 16.9122 399.544 -1.02862 100.698 +EDGE_SE3:QUAT 419 420 3.35026 -0.0314446 -0.122256 -0.00365004 0.0426982 0.074565 0.996295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.382 0.231179 21.543 399.283 0.465972 100.734 +EDGE_SE3:QUAT 420 421 3.35593 0.166072 0.00112407 0.00242136 0.0310827 0.0405178 0.998692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.24 0.0778421 15.5109 399.616 -0.974026 100.511 +EDGE_SE3:QUAT 421 422 3.41509 0.201902 -0.191458 0.00694565 0.0303708 0.0285043 0.999108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.158 0.0683133 15.1022 399.621 -2.25042 100.573 +EDGE_SE3:QUAT 422 423 3.5661 -0.0468487 -0.141353 0.00466889 0.031706 0.0513853 0.998165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.265 0.106568 15.7244 399.6 -1.72038 100.436 +EDGE_SE3:QUAT 423 424 3.3959 0.122381 -0.136459 -0.00221099 0.028264 0.0495555 0.998369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.043 0.0653658 14.2063 399.682 0.384356 100.318 +EDGE_SE3:QUAT 424 425 3.21485 -0.0281558 0.0346627 -0.00131635 0.032718 0.0404385 0.998645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.395 0.0738849 16.4284 399.574 0.132604 100.589 +EDGE_SE3:QUAT 425 426 3.30277 -0.0664087 -0.201607 -0.00151451 0.0358963 0.0358036 0.998713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.681 0.0779254 18.0413 399.486 0.199938 100.779 +EDGE_SE3:QUAT 426 427 3.2611 0.114489 -0.231325 -0.00432347 0.0279064 0.0820731 0.996226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.024 0.104743 14.1203 399.69 0.839512 99.8842 +EDGE_SE3:QUAT 427 428 3.37976 0.141219 -0.306502 0.00492196 0.0365001 0.0932484 0.994961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.627 0.233943 17.9093 399.489 -2.14954 100.041 +EDGE_SE3:QUAT 428 429 3.31658 -0.058278 -0.173215 -0.0047677 0.0330485 0.0812135 0.996137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.435 0.14616 16.7229 399.566 0.895368 100.121 +EDGE_SE3:QUAT 429 430 3.3345 0.102947 -0.105852 0.000156233 0.034264 0.0568009 0.997797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.516 0.120544 17.1465 399.538 -0.431348 100.498 +EDGE_SE3:QUAT 430 431 3.35613 0.0908043 -0.205256 0.00169349 0.0423854 0.0509452 0.9978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.316 0.172292 21.2224 399.291 -0.928951 100.996 +EDGE_SE3:QUAT 431 432 3.29621 0.199104 -0.10716 0.000674036 0.0386763 0.0592939 0.997491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.928 0.162217 19.3526 399.413 -0.652986 100.693 +EDGE_SE3:QUAT 432 433 3.45039 0.344012 -0.170228 0.00427577 0.0357102 0.0272016 0.998983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.638 0.0781758 17.8516 399.488 -1.47001 100.822 +EDGE_SE3:QUAT 433 434 3.32673 0.157965 -0.025901 0.00493611 0.0391411 0.0632202 0.99722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.924 0.191416 19.4121 399.397 -1.96357 100.663 +EDGE_SE3:QUAT 434 435 3.27829 0.135749 -0.18293 0.00782461 0.0390752 0.0262767 0.99886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.936 0.103784 19.5028 399.376 -2.54012 101.013 +EDGE_SE3:QUAT 435 436 3.56308 0.192495 0.0145542 0.000255535 0.0358269 0.083626 0.995853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.639 0.192857 17.866 399.505 -0.670078 100.191 +EDGE_SE3:QUAT 436 437 3.20551 0.0425734 -0.168717 0.00314343 0.0411661 0.0426136 0.998238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.178 0.143347 20.5886 399.328 -1.28314 101.004 +EDGE_SE3:QUAT 437 438 3.39451 0.209493 -0.20637 -0.00609025 0.0383942 0.0401134 0.998439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.935 0.0833912 19.4171 399.4 1.51819 100.896 +EDGE_SE3:QUAT 438 439 3.18075 -0.080392 -0.132056 -0.00244836 0.0211933 0.0546502 0.998278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.588 0.0393402 10.6653 399.82 0.503077 100.02 +EDGE_SE3:QUAT 439 440 3.54228 0.143921 -0.241116 -0.00178617 0.0288861 0.0790561 0.99645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.082 0.113913 14.4885 399.674 0.0806709 99.9603 +EDGE_SE3:QUAT 440 441 3.38823 -0.051158 -0.0980165 0.00506576 0.0346118 0.0626312 0.997424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.496 0.150153 17.1225 399.527 -1.94501 100.438 +EDGE_SE3:QUAT 441 442 3.27827 0.124023 -0.102063 -0.00306075 0.03675 0.0266637 0.998964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.766 0.0535922 18.4999 399.458 0.722554 100.884 +EDGE_SE3:QUAT 442 443 3.56728 -0.0719442 -0.377339 0.00151098 0.0384523 0.0590277 0.997514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.898 0.162566 19.2096 399.42 -0.898797 100.682 +EDGE_SE3:QUAT 443 444 3.62625 0.0721493 -0.156417 0.00907115 0.038502 0.0535081 0.997784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.819 0.174965 19.0018 399.398 -3.11833 100.753 +EDGE_SE3:QUAT 444 445 3.32187 0.127136 -0.110797 0.0107632 0.0416535 0.0579234 0.997394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.105 0.221544 20.5039 399.293 -3.69087 100.882 +EDGE_SE3:QUAT 445 446 3.53989 0.127564 -0.0473487 0.00085086 0.0327277 0.0607895 0.997614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.376 0.119551 16.3385 399.58 -0.64863 100.376 +EDGE_SE3:QUAT 446 447 3.58459 -0.00379123 -0.0336647 0.00902363 0.0335571 0.0578826 0.997718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.359 0.143776 16.474 399.54 -3.08555 100.455 +EDGE_SE3:QUAT 447 448 3.46325 0.173719 -0.0595293 0.00119665 0.0313979 0.0785377 0.996416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.252 0.141545 15.6076 399.619 -0.848547 100.065 +EDGE_SE3:QUAT 448 449 3.55411 0.204853 -0.184507 -0.00183088 0.0250574 0.0419659 0.998803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.819 0.04303 12.5827 399.749 0.339606 100.266 +EDGE_SE3:QUAT 449 450 3.57962 0.0782268 -0.119861 0.00601294 0.0364695 0.0370647 0.998629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.685 0.110606 18.16 399.464 -2.06445 100.797 +EDGE_SE3:QUAT 450 451 3.35634 0.127703 0.102256 0.00263903 0.0303164 0.0664934 0.997323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.161 0.11644 15.0392 399.64 -1.19077 100.194 +EDGE_SE3:QUAT 451 452 3.61229 0.184675 -0.168935 -0.000443619 0.0338697 0.0515159 0.998098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.488 0.10507 16.9758 399.547 -0.211927 100.538 +EDGE_SE3:QUAT 452 453 3.57427 0.0722839 -0.0655716 -0.000120386 0.0443509 0.0491464 0.997806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.555 0.174385 22.2828 399.223 -0.389868 101.139 +EDGE_SE3:QUAT 453 454 3.47514 0.116031 -0.215117 0.00306661 0.0433822 0.0587659 0.997324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.404 0.211947 21.6539 399.261 -1.41557 100.966 +EDGE_SE3:QUAT 454 455 3.61715 0.0685614 -0.0014102 0.00427426 0.0364222 0.0564872 0.99773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.676 0.149128 18.0947 399.476 -1.68463 100.603 +EDGE_SE3:QUAT 455 456 3.45329 0.18322 -0.121366 0.00593956 0.0422908 0.0348458 0.99848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.283 0.138198 21.1265 399.282 -2.06257 101.135 +EDGE_SE3:QUAT 456 457 3.76647 0.211655 -0.347048 -0.00120005 0.0406545 0.0878343 0.995304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.127 0.256327 20.3649 399.362 -0.345444 100.382 +EDGE_SE3:QUAT 457 458 3.4447 0.189049 -0.00781451 -0.00300216 0.0401768 0.0947784 0.994683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.093 0.264804 20.2097 399.376 0.145975 100.237 +EDGE_SE3:QUAT 458 459 3.53498 0.0785846 0.0688918 -0.00363803 0.0363592 0.022769 0.999073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.728 0.0407843 18.3058 399.467 0.925065 100.885 +EDGE_SE3:QUAT 459 460 3.60933 0.123437 -0.309198 -0.0036517 0.0329027 0.0609948 0.997589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.418 0.10786 16.5932 399.568 0.696055 100.397 +EDGE_SE3:QUAT 460 461 3.38766 0.201033 -0.133137 -0.00110512 0.047802 0.060421 0.997027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.97 0.244688 24.0531 399.101 -0.232698 101.241 +EDGE_SE3:QUAT 461 462 3.51512 0.221229 -0.173054 0.000185285 0.0357378 0.0811355 0.996062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.634 0.186145 17.8317 399.506 -0.629725 100.229 +EDGE_SE3:QUAT 462 463 3.54555 0.142099 -0.169522 -0.00174454 0.0371308 0.0534449 0.997879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.796 0.126758 18.6634 399.454 0.130929 100.684 +EDGE_SE3:QUAT 463 464 3.54701 0.145732 -0.306492 -0.00162444 0.0417141 0.0255844 0.998801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.274 0.073633 20.9976 399.305 0.276524 101.161 +EDGE_SE3:QUAT 464 465 3.62741 0.0754943 -0.233159 0.00157848 0.0330783 0.0678496 0.997146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.395 0.137739 16.4676 399.573 -0.917302 100.299 +EDGE_SE3:QUAT 465 466 3.60857 -0.0900581 -0.286237 0.00728529 0.0305249 0.0717419 0.996929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.119 0.137477 14.9226 399.627 -2.61782 100.131 +EDGE_SE3:QUAT 466 467 3.59722 0.203756 -0.0427307 0.00123878 0.0230342 0.0756318 0.996869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.671 0.0739739 11.4221 399.794 -0.719582 99.7943 +EDGE_SE3:QUAT 467 468 3.56376 0.162283 -0.100662 0.00239534 0.0418393 0.0604259 0.997293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.239 0.199929 20.8885 399.313 -1.21205 100.854 +EDGE_SE3:QUAT 468 469 3.54669 -0.0492029 0.00153818 -0.00691413 0.0312862 0.0769085 0.996523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.296 0.116788 15.9346 399.599 1.59333 100.124 +EDGE_SE3:QUAT 469 470 3.64499 0.0668751 0.0793052 0.00234607 0.0318558 0.0405192 0.998668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.304 0.0813818 15.9027 399.597 -0.957441 100.545 +EDGE_SE3:QUAT 470 471 3.69806 0.169708 -0.211487 0.00333978 0.0407945 0.047951 0.998011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.131 0.157301 20.3746 399.341 -1.38193 100.932 +EDGE_SE3:QUAT 471 472 3.49565 0.182365 -0.168005 0.00407132 0.043406 0.0733658 0.996352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.372 0.263585 21.5542 399.267 -1.84204 100.766 +EDGE_SE3:QUAT 472 473 3.62298 0.0511005 -0.266726 0.00411349 0.0369786 0.0411836 0.998459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.746 0.116532 18.4453 399.455 -1.52995 100.787 +EDGE_SE3:QUAT 473 474 3.71147 0.192303 -0.091043 0.000766188 0.0423801 0.0802065 0.995877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.295 0.261338 21.1597 399.306 -0.897664 100.605 +EDGE_SE3:QUAT 474 475 3.74325 0.0567789 -0.0913575 0.00755572 0.0344105 0.0707281 0.996873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.434 0.171419 16.8713 399.528 -2.74424 100.32 +EDGE_SE3:QUAT 475 476 3.59765 -0.10032 -0.0151919 0.00450485 0.0400644 0.0321501 0.99867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.061 0.111673 20.0368 399.358 -1.5988 101.023 +EDGE_SE3:QUAT 476 477 3.67405 0.121143 -0.100621 -0.00455539 0.0362534 0.0260496 0.998993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.719 0.044928 18.2713 399.468 1.17647 100.867 +EDGE_SE3:QUAT 477 478 3.62676 0.177563 -0.174458 0.000323787 0.0347272 0.0496277 0.998164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.56 0.108961 17.388 399.524 -0.437033 100.597 +EDGE_SE3:QUAT 478 479 3.67612 0.158047 -0.357277 0.00329788 0.0405385 0.0559371 0.997606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.096 0.178248 20.2142 399.353 -1.43126 100.832 +EDGE_SE3:QUAT 479 480 3.60555 0.204163 -0.266459 -0.000531436 0.0312755 0.0636226 0.997484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.264 0.110333 15.6541 399.616 -0.235387 100.279 +EDGE_SE3:QUAT 480 481 3.65388 0.054029 -0.316871 -0.000530778 0.0367238 0.0586977 0.9976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.747 0.140799 18.4097 399.469 -0.266269 100.6 +EDGE_SE3:QUAT 481 482 3.86591 0.0935133 -0.0553218 -0.00114809 0.0379397 0.0613083 0.997397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.868 0.154983 19.0431 399.434 -0.114833 100.634 +EDGE_SE3:QUAT 482 483 3.65019 0.18456 -0.190368 -0.00688805 0.0318349 0.0431168 0.998539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.33 0.0572282 16.127 399.58 1.79035 100.549 +EDGE_SE3:QUAT 483 484 3.69693 0.0751205 -0.291048 -0.0045718 0.0323145 0.0341515 0.998884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.367 0.0495637 16.294 399.576 1.15024 100.628 +EDGE_SE3:QUAT 484 485 3.62024 0.27103 -0.0687773 0.0025649 0.0357588 0.0346671 0.998756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.648 0.0892291 17.8855 399.491 -1.0113 100.775 +EDGE_SE3:QUAT 485 486 3.77084 0.313037 -0.115862 -0.00494253 0.0469889 0.0576826 0.997216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.9 0.208008 23.78 399.119 0.94722 101.239 +EDGE_SE3:QUAT 486 487 3.70517 0.187198 -0.129466 -0.00710188 0.0462102 0.0578585 0.997229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.815 0.191717 23.4597 399.137 1.59882 101.201 +EDGE_SE3:QUAT 487 488 3.8475 0.256771 -0.130784 -0.000338828 0.0465234 0.0393029 0.998144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.821 0.152665 23.4137 399.141 -0.254794 101.369 +EDGE_SE3:QUAT 488 489 3.78842 0.0223509 -0.0382019 -0.00473594 0.0387065 0.0733247 0.996545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.966 0.181646 19.5713 399.405 0.857249 100.53 +EDGE_SE3:QUAT 489 490 3.88276 0.158716 -0.180889 -0.00278986 0.0376293 0.089288 0.995291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.838 0.21828 18.9221 399.45 0.170197 100.199 +EDGE_SE3:QUAT 490 491 3.75782 0.083999 -0.1481 0.00176784 0.0310416 0.000483243 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.255 0.00653086 15.5727 399.614 -0.532029 100.678 +EDGE_SE3:QUAT 491 492 3.77221 -0.111307 -0.254365 -0.000353953 0.0333714 0.0400506 0.99864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.447 0.0793325 16.735 399.558 -0.157943 100.621 +EDGE_SE3:QUAT 492 493 3.58833 0.0925936 -0.145602 0.012418 0.0368591 0.0546343 0.997749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.606 0.174573 18.0496 399.428 -4.11212 100.668 +EDGE_SE3:QUAT 493 494 3.82132 0.0112118 -0.245382 0.00185225 0.0259485 0.0470038 0.998556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.862 0.0614099 12.9261 399.734 -0.797322 100.248 +EDGE_SE3:QUAT 494 495 3.82029 0.2063 -0.203608 0.00385699 0.0377809 0.0705528 0.996785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.794 0.193198 18.7319 399.443 -1.68019 100.49 +EDGE_SE3:QUAT 495 496 3.76289 0.134068 -0.0645702 -0.00767437 0.0343566 0.0773056 0.996386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.564 0.141426 17.5158 399.516 1.7717 100.266 +EDGE_SE3:QUAT 496 497 3.73 0.173224 -0.328378 9.93756e-06 0.0334099 0.0649445 0.997329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.438 0.130293 16.7054 399.563 -0.432514 100.357 +EDGE_SE3:QUAT 497 498 3.84273 0.145939 -0.220872 -0.0099672 0.0366191 0.0611349 0.997408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.773 0.113458 18.7036 399.435 2.5403 100.62 +EDGE_SE3:QUAT 498 499 3.79888 0.0821883 -0.08635 0.000589319 0.0328473 0.0138656 0.999364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.405 0.0290538 16.478 399.569 -0.266146 100.738 +EDGE_SE3:QUAT 499 500 3.83306 0.0759601 -0.253652 0.00523283 0.0411067 0.0416222 0.998274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.153 0.148353 20.5082 399.325 -1.89907 101.01 +EDGE_SE3:QUAT 500 501 3.85151 0.138466 0.128253 -0.00871914 0.0445658 0.0972962 0.994219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.635 0.317241 22.7632 399.206 1.75438 100.499 +EDGE_SE3:QUAT 501 502 3.91966 0.0524988 -0.0996591 -0.00782442 0.0423506 0.0825907 0.995653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.374 0.238589 21.5709 399.278 1.65175 100.618 +EDGE_SE3:QUAT 502 503 3.98606 0.194653 -0.345098 0.0093016 0.0447494 0.0666624 0.996728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.45 0.27673 22.0558 399.202 -3.3634 100.948 +EDGE_SE3:QUAT 503 504 3.73441 0.108589 -0.160056 -0.000885624 0.0401146 0.0374617 0.998492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.098 0.105495 20.1651 399.36 -0.0299786 100.991 +EDGE_SE3:QUAT 504 505 3.78242 0.0320403 -0.322713 0.00518112 0.0397492 0.0424067 0.998296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.01 0.141208 19.8166 399.369 -1.87961 100.926 +EDGE_SE3:QUAT 505 506 3.70364 0.0432564 -0.226615 -0.0031522 0.0382144 0.0640591 0.997209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.908 0.157551 19.2563 399.422 0.460621 100.622 +EDGE_SE3:QUAT 506 507 3.91129 0.000431945 -0.0944495 0.014738 0.0503371 0.0445072 0.997631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.09 0.277742 24.9335 398.945 -4.82965 101.609 +EDGE_SE3:QUAT 507 508 3.97862 0.213963 0.00115162 0.00966815 0.0395518 0.0219866 0.998929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.971 0.101615 19.7436 399.351 -3.05974 101.069 +EDGE_SE3:QUAT 508 509 3.96986 0.0386509 -0.109516 0.00141907 0.0341098 0.0531 0.998005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.495 0.115773 17.0344 399.542 -0.782533 100.529 +EDGE_SE3:QUAT 509 510 3.81819 -0.0859875 -0.110866 -0.00460741 0.0381203 0.0599501 0.997463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.907 0.140699 19.263 399.419 0.928046 100.676 +EDGE_SE3:QUAT 510 511 3.91914 0.03392 -0.133456 0.00473181 0.0368817 0.0258555 0.998974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.746 0.0813916 18.4424 399.453 -1.60235 100.89 +EDGE_SE3:QUAT 511 512 3.88996 -0.0281958 -0.276218 7.66819e-05 0.0307128 0.0455425 0.99849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.222 0.0776269 15.376 399.627 -0.299863 100.453 +EDGE_SE3:QUAT 512 513 3.83797 0.0297327 -0.179258 0.00505104 0.0460734 0.0228506 0.998664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.742 0.112626 23.1257 399.148 -1.71218 101.444 +EDGE_SE3:QUAT 513 514 3.71781 0.170462 -0.223852 -0.000543652 0.0436616 0.0304898 0.998581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.487 0.10293 21.9686 399.241 -0.0975144 101.249 +EDGE_SE3:QUAT 514 515 3.89482 0.0222389 0.0105008 -0.00260654 0.0327063 0.0355311 0.99883 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.398 0.0601234 16.4519 399.572 0.550567 100.629 +EDGE_SE3:QUAT 515 516 3.95329 0.0473616 -0.10755 -0.0048823 0.0429165 0.0616953 0.99716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.419 0.185512 21.7064 399.265 0.940125 100.931 +EDGE_SE3:QUAT 516 517 3.97917 0.0879153 -0.191707 -0.0045645 0.0467695 0.0576388 0.997231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.871 0.207507 23.6546 399.129 0.837162 101.223 +EDGE_SE3:QUAT 517 518 4.00829 0.0957642 -0.284959 0.00783017 0.0407684 0.0153072 0.999021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.127 0.0795602 20.4241 399.32 -2.46142 101.158 +EDGE_SE3:QUAT 518 519 3.92345 0.0291007 -0.158137 0.00369514 0.0456663 0.055015 0.997434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.664 0.22344 22.8105 399.178 -1.59391 101.153 +EDGE_SE3:QUAT 519 520 3.87629 0.0684311 -0.0609025 0.00335003 0.0368887 0.0436491 0.99836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.742 0.119191 18.4105 399.46 -1.31894 100.76 +EDGE_SE3:QUAT 520 521 3.87616 0.165536 -0.111575 0.000100772 0.0330865 0.0769809 0.996483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.403 0.151263 16.5122 399.575 -0.535451 100.168 +EDGE_SE3:QUAT 521 522 3.93336 0.138194 -0.0748747 -0.00339231 0.0507914 0.0837363 0.995187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.36 0.374812 25.6355 398.996 0.184475 101.12 +EDGE_SE3:QUAT 522 523 3.95375 -0.0797769 -0.20141 -0.00364359 0.0398334 0.0243153 0.998904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.076 0.054774 20.0711 399.362 0.899001 101.065 +EDGE_SE3:QUAT 523 524 3.88044 0.232017 -0.0105122 -0.00433242 0.0397712 0.0544828 0.997713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.075 0.139092 20.0861 399.367 0.869563 100.828 +EDGE_SE3:QUAT 524 525 3.95145 0.0683336 -0.0597149 0.00519328 0.0421946 0.0467224 0.998003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.264 0.171599 21.0369 399.292 -1.93783 101.026 +EDGE_SE3:QUAT 525 526 3.80783 0.177405 -0.0379598 0.00606555 0.036707 0.0345386 0.998711 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.71 0.106178 18.2915 399.456 -2.0634 100.828 +EDGE_SE3:QUAT 526 527 3.87202 0.222751 -0.107692 -0.00302233 0.043402 0.0773251 0.996056 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.454 0.25089 21.8679 399.262 0.244653 100.731 +EDGE_SE3:QUAT 527 528 3.95992 0.153623 -0.202136 0.00359538 0.034754 0.0135773 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.563 0.0426141 17.4177 399.514 -1.16828 100.832 +EDGE_SE3:QUAT 528 529 3.94116 0.18508 0.0194119 -0.00834187 0.0416612 0.0299994 0.998646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.271 0.058092 21.093 399.284 2.24734 101.164 +EDGE_SE3:QUAT 529 530 4.16337 0.296778 -0.180989 -0.000544162 0.0471099 0.0269403 0.998526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.899 0.105896 23.7322 399.115 -0.0842768 101.492 +EDGE_SE3:QUAT 530 531 3.98305 0.0858175 -0.0788322 0.00131538 0.0377169 0.031367 0.998795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.845 0.085739 18.9103 399.434 -0.625739 100.899 +EDGE_SE3:QUAT 531 532 4.07791 0.104417 -0.0402646 -0.00506167 0.0368959 0.0533703 0.99788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.788 0.113213 18.6525 399.452 1.12612 100.688 +EDGE_SE3:QUAT 532 533 4.16867 0.29963 -0.149733 -0.00348107 0.0333767 0.0628219 0.99746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.458 0.115394 16.8262 399.557 0.627216 100.395 +EDGE_SE3:QUAT 533 534 4.06409 0.189856 0.00061951 -0.000150181 0.0464002 0.0772561 0.995931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.771 0.298863 23.2539 399.165 -0.656439 100.906 +EDGE_SE3:QUAT 534 535 3.92174 0.2644 -0.079848 -0.00365959 0.0415589 0.027957 0.998738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.261 0.0716874 20.9533 399.306 0.865935 101.146 +EDGE_SE3:QUAT 535 536 3.98814 0.115147 -0.186112 0.00220704 0.0422129 0.0676684 0.996812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.274 0.225349 21.0572 399.305 -1.2206 100.781 +EDGE_SE3:QUAT 536 537 3.84776 0.0917744 -0.141178 -0.000639847 0.0382441 0.0431067 0.998338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.903 0.111509 19.2044 399.42 -0.132729 100.841 +EDGE_SE3:QUAT 537 538 4.11214 0.057549 -0.346564 0.00153013 0.0311056 0.0283893 0.999112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.253 0.0543652 15.5677 399.614 -0.63253 100.597 +EDGE_SE3:QUAT 538 539 3.9898 -0.0804338 -0.225186 0.000434157 0.0435439 0.0317516 0.998547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.469 0.111088 21.8883 399.246 -0.399596 101.232 +EDGE_SE3:QUAT 539 540 4.0618 0.0327376 -0.126014 -0.00810812 0.0429685 0.0745097 0.996261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.443 0.217014 21.8835 399.252 1.79518 100.784 +EDGE_SE3:QUAT 540 541 4.0698 0.119983 -0.067476 0.00244095 0.0465563 0.0615019 0.997018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.777 0.251331 23.2806 399.151 -1.28768 101.133 +EDGE_SE3:QUAT 541 542 4.14792 0.120745 0.10754 -0.0118219 0.0436373 0.0417578 0.998104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.499 0.0910137 22.2311 399.194 3.17424 101.232 +EDGE_SE3:QUAT 542 543 4.09568 -0.0551356 -0.0582114 -0.00197879 0.038979 0.0669134 0.996995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.976 0.176133 19.594 399.403 0.0781909 100.621 +EDGE_SE3:QUAT 543 544 4.08339 0.135212 -0.0655433 -0.00573837 0.0349234 0.0383151 0.998639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.599 0.0643387 17.6466 399.503 1.45289 100.728 +EDGE_SE3:QUAT 544 545 4.0795 0.0328024 -0.0783405 -0.0031355 0.0365637 0.0356038 0.998692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.749 0.0744958 18.4145 399.464 0.681555 100.819 +EDGE_SE3:QUAT 545 546 3.93024 0.105637 -0.0186476 -0.000725715 0.0356974 0.0470618 0.998254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.656 0.105706 17.9131 399.495 -0.114064 100.673 +EDGE_SE3:QUAT 546 547 3.98135 0.127568 -0.144685 0.0023848 0.0440735 0.0280316 0.998632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.52 0.109685 22.1299 399.226 -0.953066 101.286 +EDGE_SE3:QUAT 547 548 4.19208 -0.101253 -0.316889 -0.00630406 0.04349 0.0755014 0.996177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.492 0.233219 22.0668 399.245 1.24001 100.787 +EDGE_SE3:QUAT 548 549 4.14219 0.303988 0.0285385 0.00164514 0.0405065 0.0596829 0.997394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.106 0.18266 20.243 399.356 -0.966857 100.788 +EDGE_SE3:QUAT 549 550 4.14084 0.123261 0.0149417 0.008933 0.0410074 0.015638 0.998997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.142 0.0860187 20.5329 399.307 -2.79409 101.176 +EDGE_SE3:QUAT 550 551 4.2856 0.132956 -0.18382 0.000262928 0.0437396 0.0386589 0.998295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.488 0.135147 21.9803 399.241 -0.408768 101.195 +EDGE_SE3:QUAT 551 552 3.95876 0.130382 -0.147787 0.00816811 0.0370738 0.0367683 0.998602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.72 0.121011 18.4185 399.439 -2.71084 100.836 +EDGE_SE3:QUAT 552 553 4.15462 0.207674 0.0782872 -0.000929665 0.044973 0.0663773 0.99678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.621 0.23841 22.5923 399.208 -0.30627 100.978 +EDGE_SE3:QUAT 553 554 4.03899 0.195841 -0.22051 0.00321544 0.042456 0.0510249 0.997789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.308 0.179251 21.2102 399.288 -1.38509 100.998 +EDGE_SE3:QUAT 554 555 4.33492 0.0454974 -0.412621 -0.00111544 0.052059 0.025796 0.99831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.548 0.121029 26.2799 398.919 0.0731765 101.848 +EDGE_SE3:QUAT 555 556 4.14312 -0.0246469 -0.110072 -0.0011554 0.0343982 0.029454 0.998973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.543 0.0589643 17.2776 399.528 0.145964 100.745 +EDGE_SE3:QUAT 556 557 4.08848 0.269272 -0.264466 0.0038519 0.0367519 0.0358212 0.998675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.732 0.101485 18.3568 399.461 -1.41098 100.818 +EDGE_SE3:QUAT 557 558 4.21301 0.228984 -0.211934 0.000877973 0.0444548 0.0252042 0.998693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.575 0.0944777 22.3552 399.212 -0.480548 101.327 +EDGE_SE3:QUAT 558 559 4.08028 0.122719 -0.00964286 0.00081318 0.0557111 0.060287 0.996625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.018 0.344019 28.034 398.782 -0.88926 101.815 +EDGE_SE3:QUAT 559 560 4.13282 0.0802045 -0.206804 0.00882598 0.0516861 0.0158983 0.998498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.438 0.126881 25.991 398.913 -2.78857 101.875 +EDGE_SE3:QUAT 560 561 4.27962 0.0680338 -0.167726 -0.0102469 0.0431654 0.063812 0.996975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.468 0.172938 22.0431 399.227 2.52205 100.962 +EDGE_SE3:QUAT 561 562 4.13902 0.151543 -0.0770345 -0.000649686 0.0417284 0.0465179 0.998045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.265 0.143804 20.9687 399.31 -0.18612 101.007 +EDGE_SE3:QUAT 562 563 4.1572 0.0191463 -0.333908 -0.00012498 0.0486618 0.0348792 0.998206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.089 0.149372 24.5089 399.059 -0.292066 101.546 +EDGE_SE3:QUAT 563 564 4.00573 0.225083 -0.2103 -0.0103058 0.0446995 0.0477691 0.997805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.633 0.126328 22.7612 399.169 2.66035 101.233 +EDGE_SE3:QUAT 564 565 4.23684 0.0345225 -0.189857 0.00823313 0.0360932 0.0590497 0.997568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.593 0.164649 17.7733 399.475 -2.88437 100.561 +EDGE_SE3:QUAT 565 566 4.11766 0.0936709 -0.244863 0.0017354 0.0394575 0.0322478 0.998699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.018 0.0978127 19.7833 399.381 -0.768276 100.988 +EDGE_SE3:QUAT 566 567 4.09546 0.171931 -0.290686 0.00176378 0.0378795 0.0297495 0.998838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.86 0.0840211 18.9876 399.429 -0.748685 100.918 +EDGE_SE3:QUAT 567 568 4.33513 0.0646891 -0.345993 0.00105812 0.0456597 0.0578246 0.997281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.69 0.222443 22.8884 399.181 -0.831534 101.124 +EDGE_SE3:QUAT 568 569 4.31873 0.0483286 -0.177583 0.00904971 0.0520081 0.0651827 0.996476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.356 0.361562 25.7786 398.929 -3.3567 101.459 +EDGE_SE3:QUAT 569 570 4.16762 0.139206 -0.208122 0.00783038 0.0445715 0.0232743 0.998704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.538 0.120368 22.3165 399.193 -2.53981 101.353 +EDGE_SE3:QUAT 570 571 4.1774 0.100141 -0.270994 -0.00473293 0.0369625 0.0515015 0.997977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.793 0.110136 18.6735 399.45 1.04073 100.709 +EDGE_SE3:QUAT 571 572 4.21111 0.028043 -0.214451 -0.00206868 0.039383 0.043266 0.998285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.026 0.113241 19.8196 399.383 0.283874 100.906 +EDGE_SE3:QUAT 572 573 3.97529 0.0323595 -0.266289 0.00285411 0.0382002 0.0238318 0.998982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.889 0.0741784 19.1462 399.417 -1.0319 100.968 +EDGE_SE3:QUAT 573 574 4.2122 0.0110234 -0.169995 -0.00838898 0.040812 0.0631647 0.997133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.202 0.157785 20.7742 399.317 2.00148 100.813 +EDGE_SE3:QUAT 574 575 4.52554 0.0814973 -0.218838 0.000655276 0.035421 0.0434973 0.998425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.624 0.10075 17.7403 399.503 -0.499741 100.689 +EDGE_SE3:QUAT 575 576 4.20093 0.178484 -0.153546 0.00810293 0.046778 0.0331465 0.998322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.781 0.170505 23.3775 399.115 -2.7197 101.435 +EDGE_SE3:QUAT 576 577 4.45554 0.134722 -0.293898 0.0051936 0.0430419 0.0480867 0.997902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.355 0.182657 21.4607 399.264 -1.95661 101.064 +EDGE_SE3:QUAT 577 578 4.49419 0.0859528 -0.176432 0.00907723 0.0377006 0.0385214 0.998505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.766 0.132275 18.7032 399.416 -2.99988 100.857 +EDGE_SE3:QUAT 578 579 4.29297 0.133856 -0.289144 -0.00247615 0.0421615 -0.000277727 0.999108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.32 -0.0120454 21.212 399.287 0.741786 101.254 +EDGE_SE3:QUAT 579 580 4.09957 -0.0325063 -0.161072 0.00571531 0.0400305 0.0551061 0.997661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.016 0.180393 19.878 399.364 -2.14226 100.813 +EDGE_SE3:QUAT 580 581 4.53389 0.226595 -0.133671 0.00588031 0.045344 0.0351447 0.998336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.631 0.158176 22.6815 399.176 -2.06603 101.322 +EDGE_SE3:QUAT 581 582 4.27189 0.238078 -0.126906 0.00413091 0.049083 0.0431373 0.997854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.098 0.209004 24.596 399.044 -1.64324 101.503 +EDGE_SE3:QUAT 582 583 4.23315 0.245158 -0.226537 0.00632415 0.0490691 0.0698411 0.99633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.013 0.330681 24.3557 399.057 -2.55556 101.183 +EDGE_SE3:QUAT 583 584 4.25792 0.192358 -0.285872 0.00989399 0.0491534 0.0384303 0.998003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.041 0.217882 24.5135 399.019 -3.31767 101.559 +EDGE_SE3:QUAT 584 585 4.35623 0.165366 -0.264653 -0.00026488 0.0453516 0.0453778 0.99794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.676 0.167837 22.8039 399.186 -0.32231 101.24 +EDGE_SE3:QUAT 585 586 4.46245 0.192824 -0.199804 -0.0113693 0.0478818 0.0725104 0.996153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.048 0.250259 24.5244 399.053 2.71705 101.164 +EDGE_SE3:QUAT 586 587 4.39104 0.119623 -0.0441801 0.00778233 0.0374539 0.0212144 0.999043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.781 0.083764 18.7094 399.425 -2.48274 100.951 +EDGE_SE3:QUAT 587 588 4.27077 0.0866119 -0.193441 0.00690159 0.0452591 0.0504482 0.997677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.582 0.216877 22.5231 399.183 -2.50676 101.178 +EDGE_SE3:QUAT 588 589 4.31423 0.0100555 -0.00976918 -0.00279214 0.0439481 0.0345878 0.998431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.528 0.108451 22.1584 399.228 0.537056 101.246 +EDGE_SE3:QUAT 589 590 4.15984 -0.00327917 -0.0570958 0.00619587 0.0387447 0.0463107 0.998156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.892 0.148462 19.2597 399.399 -2.2053 100.836 +EDGE_SE3:QUAT 590 591 4.08242 0.195928 -0.249705 0.0100113 0.0533853 0.0866453 0.994757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.448 0.485623 26.2289 398.891 -3.8864 101.211 +EDGE_SE3:QUAT 591 592 4.34058 0.289463 -0.236897 0.0016711 0.0397709 0.0530158 0.9978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.035 0.157608 19.89 399.377 -0.913874 100.823 +EDGE_SE3:QUAT 592 593 4.19862 0.27484 -0.343434 0.00890554 0.0507502 0.0225605 0.998417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.298 0.154032 25.4663 398.953 -2.87591 101.777 +EDGE_SE3:QUAT 593 594 4.31115 0.106374 -0.105547 -0.00121344 0.0473866 0.0610982 0.997006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.919 0.242625 23.8439 399.117 -0.202034 101.205 +EDGE_SE3:QUAT 594 595 4.32924 0.0533522 -0.266254 -0.00222763 0.0416228 0.0510733 0.997825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.262 0.150912 20.9577 399.313 0.249047 100.961 +EDGE_SE3:QUAT 595 596 4.24461 0.0746417 -0.0334534 -0.000927147 0.0440286 0.0355585 0.998397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.53 0.120753 22.1589 399.229 -0.0287243 101.239 +EDGE_SE3:QUAT 596 597 4.33841 0.498751 0.0540982 0.00704792 0.0522422 0.0478354 0.997463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.467 0.273715 26.1047 398.913 -2.58425 101.685 +EDGE_SE3:QUAT 597 598 4.49115 0.110355 -0.119654 0.00193916 0.0452679 0.0362762 0.998314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.656 0.143751 22.7259 399.186 -0.898987 101.307 +EDGE_SE3:QUAT 598 599 4.50303 -0.0453035 0.00094901 0.00685618 0.0485669 0.0391669 0.998028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.006 0.201465 24.2826 399.055 -2.41472 101.505 +EDGE_SE3:QUAT 599 600 4.48083 0.313245 -0.371852 0.00752073 0.0450498 0.0344437 0.998362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.579 0.161179 22.4997 399.181 -2.54781 101.311 +EDGE_SE3:QUAT 600 601 4.37029 0.0298635 -0.182147 -0.00385803 0.0524726 0.0344165 0.998022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.614 0.150908 26.5443 398.898 0.801033 101.836 +EDGE_SE3:QUAT 601 602 4.29162 0.279554 -0.242674 -0.00682883 0.0504394 0.0410379 0.99786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.348 0.15377 25.5793 398.971 1.63518 101.654 +EDGE_SE3:QUAT 602 603 4.32291 0.10136 -0.182155 0.00542759 0.048738 0.0674561 0.996516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.992 0.312903 24.2414 399.07 -2.26075 101.195 +EDGE_SE3:QUAT 603 604 4.57205 0.00141839 -0.115226 0.0106064 0.0365894 0.0343096 0.998685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.648 0.121116 18.1365 399.439 -3.41903 100.839 +EDGE_SE3:QUAT 604 605 4.31508 0.115225 -0.287968 0.00920699 0.0401815 0.0506552 0.997865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.991 0.182157 19.8694 399.345 -3.15217 100.877 +EDGE_SE3:QUAT 605 606 4.47606 0.0393742 -0.258725 -0.00991881 0.0434635 0.0623642 0.997057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.5 0.171839 22.1768 399.219 2.43261 100.996 +EDGE_SE3:QUAT 606 607 4.3798 0.174756 -0.324664 -0.00481844 0.0450858 0.0766438 0.996027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.665 0.261783 22.8082 399.197 0.762926 100.858 +EDGE_SE3:QUAT 607 608 4.45626 0.334622 -0.174912 0.00391007 0.0512868 0.0541181 0.997209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.37 0.277577 25.6784 398.963 -1.70383 101.547 +EDGE_SE3:QUAT 608 609 4.51434 0.222591 -0.174641 0.00733794 0.0452177 0.0541297 0.997483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.564 0.231281 22.4635 399.185 -2.66963 101.135 +EDGE_SE3:QUAT 609 610 4.44196 0.124978 -0.155572 0.00380247 0.0442712 0.0441541 0.998036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.515 0.173296 22.1443 399.222 -1.51737 101.177 +EDGE_SE3:QUAT 610 611 4.43806 0.145389 -0.227869 0.00166826 0.0493904 0.0294963 0.998343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.175 0.139495 24.8567 399.029 -0.779795 101.63 +EDGE_SE3:QUAT 611 612 4.45431 -0.0354811 -0.177062 0.00208107 0.0484154 0.0178337 0.998666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.056 0.0868571 24.3773 399.063 -0.788083 101.62 +EDGE_SE3:QUAT 612 613 4.5437 0.219906 -0.195187 0.000374773 0.0532094 0.0352458 0.997961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.694 0.183726 26.831 398.875 -0.473277 101.872 +EDGE_SE3:QUAT 613 614 4.40734 0.262372 -0.324841 -0.00359312 0.0399097 0.0404801 0.998377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.086 0.102232 20.1254 399.362 0.757022 100.965 +EDGE_SE3:QUAT 614 615 4.38916 0.11042 -0.151074 -0.00502767 0.0370298 0.0610254 0.997436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.802 0.133555 18.7277 399.45 1.05857 100.607 +EDGE_SE3:QUAT 615 616 4.35209 0.0124038 -0.172293 -0.00278656 0.0482933 0.0508566 0.997534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.051 0.201582 24.3743 399.074 0.353987 101.39 +EDGE_SE3:QUAT 616 617 4.42599 0.171881 -0.135108 -0.00544077 0.0322408 0.0307062 0.998994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.359 0.0398799 16.2666 399.575 1.4327 100.65 +EDGE_SE3:QUAT 617 618 4.61995 0.282469 -0.162463 2.17897e-05 0.0475854 0.005915 0.99885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.962 0.0244736 23.9816 399.094 -0.061121 101.594 +EDGE_SE3:QUAT 618 619 4.49564 0.227836 -0.0659887 -0.000371735 0.0406727 0.0227115 0.998914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.159 0.0665129 20.4501 399.34 -0.0697795 101.112 +EDGE_SE3:QUAT 619 620 4.43863 0.344181 -0.209121 0.00138058 0.0414764 0.00843103 0.999103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.244 0.032395 20.8551 399.312 -0.480744 101.204 +EDGE_SE3:QUAT 620 621 4.39079 0.243594 -0.142127 -0.000974133 0.0497021 0.050404 0.997491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.219 0.220952 25.0386 399.023 -0.195569 101.485 +EDGE_SE3:QUAT 621 622 4.38629 0.127724 -0.109179 0.00352166 0.0518086 0.0385024 0.997908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.47 0.20678 26.0285 398.934 -1.43525 101.738 +EDGE_SE3:QUAT 622 623 4.318 0.166077 0.0118998 -0.00853229 0.0557395 0.0705304 0.995915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.111 0.352242 28.4193 398.753 1.78397 101.745 +EDGE_SE3:QUAT 623 624 4.46395 0.299958 0.0533495 -0.00147237 0.0429495 0.0521378 0.997715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.403 0.167735 21.6071 399.27 0.0015878 101.026 +EDGE_SE3:QUAT 624 625 4.55022 0.0422739 -0.0393174 -0.00698776 0.0447311 0.0510042 0.997672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.635 0.153736 22.6879 399.189 1.64118 101.178 +EDGE_SE3:QUAT 625 626 4.60777 0.170551 -0.294149 0.00248164 0.0386126 0.0583861 0.997544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.905 0.165621 19.2579 399.414 -1.18599 100.697 +EDGE_SE3:QUAT 626 627 4.58635 0.0437147 -0.247564 -0.00153561 0.0537298 0.0604624 0.996722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.762 0.308555 27.1037 398.864 -0.169927 101.669 +EDGE_SE3:QUAT 627 628 4.56696 0.121635 -0.0161831 -0.00841971 0.0425449 0.0618814 0.997141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.392 0.168381 21.6516 399.26 1.99999 100.932 +EDGE_SE3:QUAT 628 629 4.58803 0.231626 -0.137042 -0.00541135 0.0413171 0.0228632 0.99887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.233 0.0472597 20.8481 399.308 1.43171 101.164 +EDGE_SE3:QUAT 629 630 4.69801 0.123747 -0.334257 -0.00826222 0.0399255 0.0307908 0.998694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.085 0.0546777 20.2121 399.341 2.228 101.058 +EDGE_SE3:QUAT 630 631 4.58682 0.0279869 -0.174891 0.00525439 0.04005 0.0226593 0.998927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.063 0.0876054 20.0548 399.354 -1.74792 101.079 +EDGE_SE3:QUAT 631 632 4.43235 0.257981 -0.246344 -0.0132919 0.0498275 0.062245 0.996728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.295 0.21512 25.5513 398.957 3.36244 101.458 +EDGE_SE3:QUAT 632 633 4.67311 0.342888 -0.255237 -0.00370972 0.04022 0.0406352 0.998357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.119 0.103926 20.286 399.352 0.78822 100.982 +EDGE_SE3:QUAT 633 634 4.70961 0.101084 -0.302912 -0.0031949 0.0375198 0.0345815 0.998692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.842 0.0759015 18.8995 399.436 0.700243 100.877 +EDGE_SE3:QUAT 634 635 4.5897 0.252222 -0.198263 0.000339079 0.0434314 0.0308657 0.998579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.457 0.107073 21.8341 399.249 -0.363013 101.231 +EDGE_SE3:QUAT 635 636 4.51069 0.200092 -0.303932 -0.00211364 0.0455004 0.0219354 0.998721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.709 0.0722516 22.9344 399.172 0.436533 101.414 +EDGE_SE3:QUAT 636 637 4.69478 0.255173 -0.0433796 -0.000693463 0.0484985 0.0515347 0.997493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.061 0.216312 24.412 399.071 -0.278939 101.389 +EDGE_SE3:QUAT 637 638 4.58338 0.0998904 -0.327242 -0.00300349 0.0457886 0.0401604 0.998139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.746 0.138604 23.1032 399.163 0.538279 101.322 +EDGE_SE3:QUAT 638 639 4.52351 0.0892914 -0.0622867 0.0107716 0.0480132 0.0551111 0.997267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.84 0.278337 23.763 399.069 -3.7303 101.314 +EDGE_SE3:QUAT 639 640 4.53851 0.151947 -0.268693 0.00204332 0.0532096 0.00376764 0.998574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.706 0.0314987 26.8653 398.867 -0.647172 102.001 +EDGE_SE3:QUAT 640 641 4.61971 0.236515 -0.218548 -0.00475927 0.043382 0.0331677 0.998496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.468 0.0917638 21.9093 399.242 1.14026 101.229 +EDGE_SE3:QUAT 641 642 4.58013 0.130569 -0.0589895 -0.00783383 0.0476348 0.0801299 0.995615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403 0.295435 24.2519 399.092 1.59396 100.996 +EDGE_SE3:QUAT 642 643 4.5533 8.58184e-06 -0.145173 0.00356616 0.0467169 0.0342763 0.998314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.819 0.152903 23.4364 399.131 -1.37575 101.415 +EDGE_SE3:QUAT 643 644 4.56742 0.318652 -0.223275 -0.00250465 0.0461095 0.0601401 0.997121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.775 0.220194 23.2425 399.16 0.206678 101.138 +EDGE_SE3:QUAT 644 645 4.69144 0.086352 -0.252866 0.00124741 0.0483225 0.0476904 0.997692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.025 0.207857 24.2716 399.077 -0.820134 101.411 +EDGE_SE3:QUAT 645 646 4.47829 0.286719 -0.328534 -0.0030017 0.0525851 0.0315759 0.998113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.627 0.14205 26.5832 398.895 0.574013 101.86 +EDGE_SE3:QUAT 646 647 4.5677 0.304649 -0.263829 -0.0004798 0.0444648 0.0133167 0.998922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.584 0.0455329 22.3874 399.21 0.0278474 101.376 +EDGE_SE3:QUAT 647 648 4.61671 0.135063 -0.248071 -0.00761937 0.0463643 0.057471 0.997241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.836 0.189187 23.5558 399.129 1.7551 101.219 +EDGE_SE3:QUAT 648 649 4.59082 -0.0719269 -0.282693 -0.000953232 0.0440337 0.0686087 0.996671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.511 0.236042 22.111 399.241 -0.307032 100.888 +EDGE_SE3:QUAT 649 650 4.59289 0.202558 -0.197916 0.00401889 0.0459749 0.0436473 0.99798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.713 0.185537 23.0088 399.161 -1.59084 101.29 +EDGE_SE3:QUAT 650 651 4.6122 0.311188 -0.346963 -0.00287781 0.0480983 0.0531279 0.997425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.027 0.209021 24.2762 399.082 0.361733 101.354 +EDGE_SE3:QUAT 651 652 4.58803 0.210786 -0.337134 -0.00584447 0.0463683 0.0389263 0.998149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.825 0.123825 23.4669 399.132 1.39291 101.384 +EDGE_SE3:QUAT 652 653 4.63035 0.0195722 -0.322998 -0.00291785 0.0515846 0.0515392 0.997334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.484 0.233791 26.0633 398.944 0.355331 101.618 +EDGE_SE3:QUAT 653 654 4.64071 -0.0476349 -0.390215 -0.00125201 0.0448528 0.036477 0.998327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.627 0.12728 22.5856 399.199 0.0547522 101.285 +EDGE_SE3:QUAT 654 655 4.49805 0.208642 -0.108222 0.00998199 0.0436838 0.0740728 0.996246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.299 0.289807 21.4202 399.241 -3.61914 100.774 +EDGE_SE3:QUAT 655 656 4.99066 0.168336 -0.259591 -0.00170113 0.0500828 0.0442569 0.997763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.278 0.192819 25.2635 399.004 0.0776961 101.575 +EDGE_SE3:QUAT 656 657 4.59405 0.135321 -0.253109 0.00205723 0.0425058 0.0435213 0.998146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.333 0.150914 21.2954 399.285 -0.976603 101.076 +EDGE_SE3:QUAT 657 658 4.82022 -0.00036991 -0.219453 -0.00170541 0.0547099 0.0538692 0.997047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.909 0.283561 27.6262 398.817 -0.0599851 101.823 +EDGE_SE3:QUAT 658 659 4.69842 0.0679796 -0.276004 -0.00170712 0.0408828 0.0426035 0.998254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.182 0.12185 20.5718 399.335 0.168777 100.996 +EDGE_SE3:QUAT 659 660 4.77755 0.0719081 -0.0206436 0.00478128 0.0524947 0.0265411 0.998257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.569 0.16006 26.4052 398.898 -1.69338 101.873 +EDGE_SE3:QUAT 660 661 4.77593 0.0848698 -0.202075 0.00570243 0.0435476 0.0814737 0.995707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.347 0.296875 21.4984 399.265 -2.40234 100.642 +EDGE_SE3:QUAT 661 662 4.71358 0.0893484 -0.151853 -0.0056462 0.0469087 0.0611473 0.99701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.894 0.21808 23.7671 399.12 1.12637 101.197 +EDGE_SE3:QUAT 662 663 4.75095 0.0201234 -0.328919 0.010999 0.0473704 0.0218647 0.998577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.84 0.144091 23.7101 399.073 -3.48245 101.556 +EDGE_SE3:QUAT 663 664 4.58738 0.117525 -0.069831 0.000707481 0.0428904 0.0846902 0.995484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.346 0.281879 21.4044 399.292 -0.926154 100.56 +EDGE_SE3:QUAT 664 665 4.78619 0.0194477 -0.149245 -0.00577341 0.0469036 0.0467989 0.997786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.893 0.159262 23.7521 399.115 1.29578 101.352 +EDGE_SE3:QUAT 665 666 4.77068 0.138414 -0.16816 -0.00209926 0.0468055 0.0299639 0.998452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.867 0.108868 23.6025 399.125 0.353702 101.458 +EDGE_SE3:QUAT 666 667 4.84049 0.248311 -0.17468 0.00209191 0.0506885 0.0368522 0.998032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.335 0.183103 25.4934 398.98 -0.985237 101.671 +EDGE_SE3:QUAT 667 668 4.8285 0.100505 -0.349505 0.00355429 0.0473411 0.0378413 0.998155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.892 0.171054 23.7421 399.109 -1.40894 101.43 +EDGE_SE3:QUAT 668 669 4.88883 0.14119 -0.46285 0.00418329 0.041818 0.0288052 0.998701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.254 0.109239 20.947 399.3 -1.48531 101.146 +EDGE_SE3:QUAT 669 670 4.75482 0.0806364 -0.0462016 0.00413188 0.0546637 0.0361905 0.99784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.865 0.220741 27.4921 398.811 -1.61127 101.972 +EDGE_SE3:QUAT 670 671 4.71246 0.175771 -0.371031 -0.00296919 0.0553348 0.0418831 0.997585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.017 0.216203 27.9982 398.781 0.43847 101.995 +EDGE_SE3:QUAT 671 672 4.97834 0.0192568 -0.103205 0.00408571 0.0439415 0.0402932 0.998213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.479 0.158855 21.985 399.232 -1.56599 101.19 +EDGE_SE3:QUAT 672 673 4.82775 0.142154 -0.256223 0.0041098 0.0494695 0.0699201 0.996317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.101 0.326899 24.6559 399.046 -1.90014 101.211 +EDGE_SE3:QUAT 673 674 4.82017 0.176759 -0.338064 0.00016648 0.0523614 0.0317526 0.998123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.58 0.159367 26.4057 398.909 -0.370504 101.833 +EDGE_SE3:QUAT 674 675 4.9748 0.27584 -0.316333 0.00065215 0.0484311 0.0648798 0.996717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.025 0.277898 24.2939 399.082 -0.80665 101.22 +EDGE_SE3:QUAT 675 676 4.61906 0.20413 -0.273103 0.000199544 0.045717 0.0416128 0.998087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.718 0.158543 22.9846 399.171 -0.43033 101.296 +EDGE_SE3:QUAT 676 677 4.86599 0.0423888 -0.306918 0.0031525 0.0452956 0.0409932 0.998127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.644 0.166736 22.6958 399.186 -1.30328 101.27 +EDGE_SE3:QUAT 677 678 4.93698 0.26028 -0.2249 -0.00234516 0.045256 0.0275067 0.998594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.681 0.0910932 22.8149 399.181 0.457529 101.371 +EDGE_SE3:QUAT 678 679 4.73583 0.13002 -0.312245 -0.00421778 0.0423655 0.0362245 0.998436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.353 0.0994717 21.3844 399.279 0.959774 101.143 +EDGE_SE3:QUAT 679 680 4.86816 0.0790258 -0.165199 0.00458291 0.0487119 0.0321988 0.998283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.061 0.162048 24.4438 399.053 -1.67125 101.565 +EDGE_SE3:QUAT 680 681 4.89984 0.228714 -0.238236 -0.00245195 0.0486454 0.0520135 0.997458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.093 0.211244 24.5428 399.062 0.239838 101.401 +EDGE_SE3:QUAT 681 682 4.82551 0.128119 -0.207736 0.00413686 0.0459534 0.0317978 0.998429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.725 0.141482 23.0441 399.157 -1.51921 101.383 +EDGE_SE3:QUAT 682 683 4.80184 0.00748369 -0.0880933 -0.00451399 0.0438414 0.0616986 0.997121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.522 0.195586 22.1626 399.235 0.819158 100.986 +EDGE_SE3:QUAT 683 684 4.97453 0.156508 -0.317605 -0.00132884 0.0489409 0.0815126 0.995469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.095 0.346133 24.5917 399.071 -0.381652 101.014 +EDGE_SE3:QUAT 684 685 4.80416 0.100665 -0.078458 0.00546875 0.052594 0.0110405 0.99854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.599 0.087259 26.5121 398.887 -1.74103 101.947 +EDGE_SE3:QUAT 685 686 4.91193 0.0590685 -0.250704 -0.00190285 0.051203 0.0202671 0.998481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.435 0.0861693 25.8522 398.952 0.366615 101.813 +EDGE_SE3:QUAT 686 687 4.72536 0.254034 -0.280541 0.00160615 0.0490227 0.0609556 0.996935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.094 0.27237 24.5727 399.058 -1.06057 101.308 +EDGE_SE3:QUAT 687 688 4.75524 0.229598 -0.219658 0.000856414 0.0494817 0.032707 0.998239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.19 0.149975 24.9121 399.026 -0.56904 101.617 +EDGE_SE3:QUAT 688 689 4.9573 0.231367 -0.269147 0.00973946 0.0529911 0.0844293 0.994972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.41 0.467462 26.0653 398.906 -3.77589 101.222 +EDGE_SE3:QUAT 689 690 4.77554 0.273571 -0.0551941 -0.00416847 0.0379184 0.0261354 0.99893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.881 0.0516801 19.1095 399.42 1.05153 100.952 +EDGE_SE3:QUAT 690 691 4.88762 0.0357302 -0.223774 0.00207066 0.0516518 0.0417417 0.99779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.459 0.213341 25.9725 398.943 -1.03418 101.7 +EDGE_SE3:QUAT 691 692 4.81846 0.145556 -0.237586 0.00106073 0.0455554 0.0357183 0.998322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.697 0.139386 22.8936 399.176 -0.633666 101.33 +EDGE_SE3:QUAT 692 693 4.9306 0.16921 -0.199292 -0.0105493 0.049422 0.0438383 0.99776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.218 0.140293 25.164 398.99 2.72581 101.588 +EDGE_SE3:QUAT 693 694 4.84945 0.253784 -0.235495 0.00746433 0.0478749 0.0265048 0.998474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.935 0.147877 23.9911 399.074 -2.47305 101.55 +EDGE_SE3:QUAT 694 695 4.74567 0.176565 -0.0688786 -0.00238828 0.0415492 0.0696172 0.996705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.247 0.207637 20.9094 399.322 0.145711 100.731 +EDGE_SE3:QUAT 695 696 4.72455 0.182174 -0.351116 -0.00631141 0.0528956 0.0204661 0.99837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.67 0.0677553 26.7781 398.868 1.67138 101.955 +EDGE_SE3:QUAT 696 697 4.79913 0.104392 -0.298193 0.00169043 0.0491825 0.03209 0.998273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.146 0.149766 24.7433 399.038 -0.810126 101.599 +EDGE_SE3:QUAT 697 698 4.9526 -0.0545478 -0.158798 -0.00210915 0.0603723 0.0482261 0.997008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.776 0.307213 30.5722 398.555 0.0714514 102.349 +EDGE_SE3:QUAT 698 699 4.82726 0.436867 -0.0359374 3.76551e-06 0.0503246 0.0180631 0.99857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.313 0.0832889 25.3792 398.989 -0.176938 101.755 +EDGE_SE3:QUAT 699 700 4.94314 0.14087 -0.139945 -0.00380147 0.0414093 0.0247497 0.998828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.244 0.0604608 20.8753 399.31 0.935118 101.154 +EDGE_SE3:QUAT 700 701 5.04451 0.244174 -0.161839 0.00616036 0.0479661 0.0356532 0.998193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.945 0.179211 24.0118 399.079 -2.17014 101.491 +EDGE_SE3:QUAT 701 702 4.84351 0.105472 -0.29265 -0.00521351 0.0414339 0.0514911 0.9978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.255 0.138701 20.9556 399.31 1.1398 100.96 +EDGE_SE3:QUAT 702 703 4.92655 0.161364 -0.0337247 -0.00394707 0.0511533 0.00947743 0.998638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.426 0.0229962 25.8334 398.948 1.0826 101.846 +EDGE_SE3:QUAT 703 704 4.92279 0.129379 -0.302255 0.00218559 0.0574656 0.0632514 0.996339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.253 0.391248 28.8716 398.708 -1.34949 101.913 +EDGE_SE3:QUAT 704 705 4.8111 0.245733 -0.30226 0.000497371 0.0454268 0.0448401 0.997961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.679 0.169851 22.822 399.183 -0.545747 101.247 +EDGE_SE3:QUAT 705 706 5.0641 0.15892 -0.225412 0.00386824 0.0454939 0.0305406 0.99849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.673 0.132909 22.8196 399.174 -1.42529 101.361 +EDGE_SE3:QUAT 706 707 4.80976 0.157741 -0.169973 -0.00522244 0.051762 0.0347833 0.99804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.521 0.140821 26.2087 398.923 1.20857 101.788 +EDGE_SE3:QUAT 707 708 4.8845 0.108034 -0.261472 0.00620177 0.0478131 0.0738236 0.996105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.85 0.329264 23.693 399.108 -2.54139 101.037 +EDGE_SE3:QUAT 708 709 4.80948 0.262969 -0.0422534 0.00333547 0.0493821 0.0445191 0.997782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.143 0.21354 24.7648 399.034 -1.42154 101.511 +EDGE_SE3:QUAT 709 710 4.88789 0.0453553 -0.263956 -0.00359434 0.0432883 0.0454621 0.998021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.455 0.138665 21.8457 399.252 0.688862 101.121 +EDGE_SE3:QUAT 710 711 4.96909 0.0945721 -0.235013 0.00224705 0.0468079 0.0454087 0.997869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.83 0.190752 23.4762 399.133 -1.08455 101.329 +EDGE_SE3:QUAT 711 712 4.957 0.20409 -0.166317 -0.00249944 0.0574774 -0.000949814 0.998343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.331 -0.0219267 29.0724 398.677 0.753934 102.341 +EDGE_SE3:QUAT 712 713 4.82769 -0.0779356 -0.0859007 -0.000581395 0.0559116 0.03584 0.997792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.089 0.200708 28.2433 398.757 -0.211747 102.08 +EDGE_SE3:QUAT 713 714 4.99237 0.226358 -0.201009 0.00665484 0.0453112 0.0463923 0.997873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.599 0.201867 22.5823 399.18 -2.39728 101.223 +EDGE_SE3:QUAT 714 715 4.847 0.185863 -0.273731 -0.00676007 0.0579456 0.0600704 0.996488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.43 0.327544 29.4712 398.658 1.34428 102.045 +EDGE_SE3:QUAT 715 716 4.91373 0.20578 -0.241385 0.0125832 0.0511041 0.0521604 0.997251 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.207 0.30864 25.3097 398.936 -4.26937 101.57 +EDGE_SE3:QUAT 716 717 5.03791 0.0643769 -0.223127 -0.00375243 0.0453147 0.0579793 0.997282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.69 0.198977 22.8842 399.184 0.607505 101.119 +EDGE_SE3:QUAT 717 718 5.0882 0.286328 -0.308134 -0.000343375 0.0565173 0.0408488 0.997566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.173 0.235662 28.5414 398.733 -0.340929 102.088 +EDGE_SE3:QUAT 718 719 5.13539 0.131652 -0.36562 -0.00780436 0.050103 0.0834029 0.995225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.317 0.344103 25.5123 399 1.51555 101.114 +EDGE_SE3:QUAT 719 720 5.11758 0.004806 -0.354268 -0.00357103 0.0433379 0.0626952 0.997085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.458 0.198155 21.8706 399.256 0.534817 100.937 +EDGE_SE3:QUAT 720 721 5.04158 0.136478 -0.222813 -0.000555232 0.0470677 0.0625536 0.996931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.872 0.247981 23.6529 399.131 -0.40843 101.163 +EDGE_SE3:QUAT 721 722 4.94569 0.0317493 -0.155873 -0.00364467 0.0550589 0.0566462 0.996868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.975 0.291903 27.8693 398.799 0.484753 101.829 +EDGE_SE3:QUAT 722 723 4.99568 0.172668 -0.416876 0.011055 0.051379 0.0351434 0.997999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.322 0.22731 25.6538 398.923 -3.64454 101.749 +EDGE_SE3:QUAT 723 724 5.0321 0.0729174 -0.381444 0.0016658 0.0420669 0.0160365 0.998985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.305 0.0588773 21.1428 399.293 -0.629364 101.219 +EDGE_SE3:QUAT 724 725 5.10744 0.304035 -0.365794 0.00407836 0.052808 0.0745967 0.995806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.531 0.394463 26.335 398.917 -1.98055 101.38 +EDGE_SE3:QUAT 725 726 5.23308 0.150503 -0.271173 -0.00321426 0.0548982 0.00887423 0.998447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.952 0.0291556 27.7567 398.791 0.863287 102.129 +EDGE_SE3:QUAT 726 727 5.00387 -0.0204341 -0.221934 -0.00762111 0.057321 0.0545154 0.996837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.339 0.281189 29.1718 398.678 1.66875 102.064 +EDGE_SE3:QUAT 727 728 4.83586 0.262332 -0.307353 0.00235496 0.0446543 0.0546261 0.997505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.562 0.206883 22.3423 399.215 -1.18011 101.094 +EDGE_SE3:QUAT 728 729 5.13506 0.159915 -0.107686 -0.00158319 0.0538211 -9.99756e-06 0.998549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.795 -0.00952256 27.1855 398.841 0.471547 102.049 +EDGE_SE3:QUAT 729 730 5.14321 0.185646 -0.461683 -0.000850193 0.0426207 0.0258977 0.998755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.372 0.0815192 21.4468 399.275 0.0382648 101.212 +EDGE_SE3:QUAT 730 731 5.11076 0.142116 -0.190949 0.00388874 0.0520324 0.0259284 0.998301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.514 0.149487 26.1848 398.918 -1.41922 101.841 +EDGE_SE3:QUAT 731 732 5.00292 0.032622 -0.351662 -0.00130486 0.0484643 0.0590609 0.997076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.056 0.244978 24.4012 399.075 -0.167523 101.304 +EDGE_SE3:QUAT 732 733 5.1493 0.111485 -0.309985 0.000682062 0.0544303 0.0394343 0.997738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.861 0.216544 27.4428 398.825 -0.616435 101.932 +EDGE_SE3:QUAT 733 734 5.02261 -0.0151599 -0.395022 -0.00856007 0.0474286 0.0667321 0.996606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.976 0.233265 24.1556 399.088 1.93838 101.185 +EDGE_SE3:QUAT 734 735 5.08378 0.10967 -0.160555 -0.0042743 0.0468054 0.0646754 0.996799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.872 0.237357 23.6624 399.132 0.685623 101.137 +EDGE_SE3:QUAT 735 736 4.96436 0.347592 -0.0562935 0.0080953 0.0527009 0.0338592 0.998003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.547 0.215783 26.4073 398.882 -2.75656 101.846 +EDGE_SE3:QUAT 736 737 5.15269 0.240358 -0.326321 -0.00139341 0.0486101 0.0259038 0.998481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.092 0.104053 24.5145 399.057 0.171378 101.601 +EDGE_SE3:QUAT 737 738 5.13317 0.140882 -0.236203 -0.00237701 0.0573812 0.0418101 0.997474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.317 0.236446 29.0389 398.691 0.24751 102.158 +EDGE_SE3:QUAT 738 739 5.01557 0.123123 -0.408925 0.00385136 0.0482205 0.0261349 0.998487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.013 0.130056 24.2295 399.071 -1.39334 101.569 +EDGE_SE3:QUAT 739 740 5.0204 -0.0823697 -0.284228 -0.00272872 0.0516524 0.00589332 0.998644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.494 0.0131227 26.0782 398.93 0.754305 101.884 +EDGE_SE3:QUAT 740 741 5.10069 0.104287 -0.153915 0.000113087 0.0500381 0.0512809 0.99743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.253 0.233361 25.1744 399.012 -0.531521 101.496 +EDGE_SE3:QUAT 741 742 5.0754 -0.013166 -0.118819 0.00840213 0.0472423 0.048616 0.997664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.801 0.235007 23.5002 399.105 -2.95509 101.329 +EDGE_SE3:QUAT 742 743 5.04127 0.11027 -0.188268 -0.00108499 0.0552664 0.0373427 0.997773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.997 0.201388 27.92 398.786 -0.0737078 102.019 +EDGE_SE3:QUAT 743 744 5.12915 0.0372705 -0.328298 0.00472243 0.0472384 0.0377314 0.99816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.867 0.175482 23.6625 399.111 -1.75584 101.424 +EDGE_SE3:QUAT 744 745 5.18019 -0.115299 -0.200111 0.00164802 0.055715 0.0724719 0.995812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.985 0.415489 27.9491 398.793 -1.2705 101.643 +EDGE_SE3:QUAT 745 746 4.96612 0.298684 -0.216537 0.00573372 0.0477357 0.0465095 0.99776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.903 0.219075 23.8451 399.094 -2.14298 101.379 +EDGE_SE3:QUAT 746 747 5.03097 -0.0854337 -0.22582 0.0054183 0.0530673 0.0343779 0.997984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.629 0.206415 26.6505 398.876 -1.96623 101.865 +EDGE_SE3:QUAT 747 748 5.2337 0.0856714 -0.305334 -0.00117869 0.0501509 0.0849936 0.995118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.244 0.379939 25.1898 399.028 -0.479072 101.038 +EDGE_SE3:QUAT 748 749 5.26509 0.0247955 -0.384943 0.00483488 0.0413374 0.0475623 0.998001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.174 0.166107 20.6078 399.321 -1.83037 100.968 +EDGE_SE3:QUAT 749 750 5.1928 0.367558 -0.188986 -0.00438092 0.0455701 0.0407319 0.998121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.725 0.132936 23.0263 399.167 0.946035 101.31 +EDGE_SE3:QUAT 750 751 5.25921 0.179427 -0.0422579 -0.00123158 0.0512168 0.022152 0.998441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.435 0.0989636 25.8504 398.952 0.147845 101.804 +EDGE_SE3:QUAT 751 752 4.99562 0.0922855 -0.160848 0.00672089 0.0521825 0.0262507 0.99827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.508 0.167597 26.2136 398.905 -2.26707 101.855 +EDGE_SE3:QUAT 752 753 5.15008 -0.209059 -0.275634 0.00558167 0.051249 0.0356928 0.998032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.377 0.200163 25.7062 398.951 -2.01766 101.72 +EDGE_SE3:QUAT 753 754 4.94842 0.0104051 -0.209326 0.00894546 0.0498093 0.00976359 0.998671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.198 0.0925268 25.064 398.986 -2.76082 101.76 +EDGE_SE3:QUAT 754 755 5.02932 0.076045 -0.171217 0.00360692 0.048394 0.0396379 0.998035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.02 0.186253 24.272 399.07 -1.4486 101.486 +EDGE_SE3:QUAT 755 756 5.36261 0.0304361 -0.355689 0.00118132 0.0510611 0.0372058 0.998002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.392 0.182604 25.7046 398.965 -0.719683 101.696 +EDGE_SE3:QUAT 756 757 5.12642 0.00873206 -0.305722 -0.00340589 0.0549734 0.0120118 0.99841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.964 0.0454245 27.8015 398.788 0.887074 102.129 +EDGE_SE3:QUAT 757 758 5.09088 0.0265784 -0.387801 -0.001705 0.0517722 0.0371597 0.997966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.508 0.171852 26.1366 398.933 0.136401 101.756 +EDGE_SE3:QUAT 758 759 5.17741 0.185837 -0.246811 0.00636488 0.0506059 -0.014871 0.998588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.352 -0.0341189 25.5841 398.963 -1.75156 101.804 +EDGE_SE3:QUAT 759 760 4.99066 0.0269255 -0.272423 0.00131919 0.0586887 0.0442913 0.997292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.482 0.286228 29.6097 398.637 -0.889902 102.231 +EDGE_SE3:QUAT 760 761 5.33196 0.0395832 -0.0656167 -0.00143194 0.0623016 0.0367254 0.99738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.093 0.250892 31.5716 398.456 -0.00935375 102.617 +EDGE_SE3:QUAT 761 762 5.0744 0.139963 -0.525425 0.00424646 0.0409045 0.0793943 0.995995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.09 0.252227 20.2462 399.352 -1.91009 100.523 +EDGE_SE3:QUAT 762 763 5.05055 0.188472 -0.369217 0.00853083 0.0528659 0.0125811 0.998486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.609 0.113513 26.6207 398.864 -2.66926 101.973 +EDGE_SE3:QUAT 763 764 5.31834 0.2129 -0.2007 0.00339368 0.0502074 0.067604 0.996442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.211 0.323326 25.0762 399.016 -1.6726 101.298 +EDGE_SE3:QUAT 764 765 5.10367 0.0125937 -0.33263 -0.000606843 0.0566192 0.0243179 0.998099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.201 0.138504 28.6235 398.721 -0.0833224 102.209 +EDGE_SE3:QUAT 765 766 5.23799 0.046888 -0.332553 0.00558715 0.0539631 0.0440647 0.997555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.734 0.264118 27.0545 398.843 -2.12305 101.85 +EDGE_SE3:QUAT 766 767 5.11997 0.302825 -0.221093 -0.00286512 0.0545978 0.037965 0.997782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.91 0.189474 27.6168 398.811 0.454362 101.969 +EDGE_SE3:QUAT 767 768 5.15075 0.180305 -0.330729 -0.00332582 0.0525364 0.0442789 0.997631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.62 0.204072 26.567 398.9 0.541848 101.761 +EDGE_SE3:QUAT 768 769 5.39527 0.0977658 -0.12326 -0.00450544 0.0564719 0.0324213 0.997867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.193 0.160938 28.617 398.722 0.989732 102.164 +EDGE_SE3:QUAT 769 770 5.21957 -0.0183566 -0.0775419 -0.00921468 0.0550279 0.0296662 0.998001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.981 0.108375 27.9543 398.763 2.42957 102.095 +EDGE_SE3:QUAT 770 771 5.11023 0.0165693 -0.360401 -0.00323894 0.0488521 0.0326928 0.998266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.128 0.125096 24.6725 399.045 0.656241 101.584 +EDGE_SE3:QUAT 771 772 5.19766 0.226146 -0.340504 -0.00468706 0.0527977 0.0474568 0.997466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.663 0.214988 26.7407 398.886 0.912896 101.758 +EDGE_SE3:QUAT 772 773 5.22283 0.251145 0.00810585 0.00235768 0.0548789 0.0368232 0.997811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.913 0.215629 27.6414 398.804 -1.09089 101.985 +EDGE_SE3:QUAT 773 774 5.08066 0.17895 -0.0709691 0.000364301 0.0459354 0.0267766 0.998585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.752 0.104336 23.1169 399.159 -0.348103 101.414 +EDGE_SE3:QUAT 774 775 5.2177 0.199758 -0.191193 0.00763267 0.0565565 0.0145746 0.998264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.146 0.133017 28.5205 398.707 -2.42917 102.251 +EDGE_SE3:QUAT 775 776 5.26067 0.207537 -0.439405 0.00653254 0.0456968 0.0448452 0.997927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.649 0.198974 22.7916 399.166 -2.34997 101.262 +EDGE_SE3:QUAT 776 777 5.24894 0.103057 -0.373697 -0.00703607 0.0543672 -0.00717088 0.99847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.843 -0.0811013 27.433 398.804 2.16984 102.096 +EDGE_SE3:QUAT 777 778 5.26307 0.0661414 -0.149344 -0.00334203 0.0553748 0.0742301 0.995697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.004 0.395155 27.9975 398.799 0.202292 101.618 +EDGE_SE3:QUAT 778 779 5.48233 0.00571877 -0.339827 0.00146251 0.0539151 0.0419855 0.997661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.778 0.230179 27.1506 398.848 -0.872007 101.869 +EDGE_SE3:QUAT 779 780 5.23838 0.246089 -0.220833 0.00448337 0.046396 0.0163989 0.998778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.792 0.0863562 23.322 399.136 -1.48568 101.492 +EDGE_SE3:QUAT 780 781 5.32681 0.209297 -0.116294 -0.00818975 0.0518953 0.00652804 0.998598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.51 -0.0148826 26.2248 398.902 2.37461 101.922 +EDGE_SE3:QUAT 781 782 5.31848 0.092892 -0.216081 0.00826843 0.0465932 0.0460477 0.997818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.73 0.21877 23.1915 399.128 -2.88618 101.312 +EDGE_SE3:QUAT 782 783 5.35902 0.258926 -0.336743 -0.00631734 0.0586041 0.0701067 0.995797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.525 0.401776 29.7981 398.638 1.09196 101.965 +EDGE_SE3:QUAT 783 784 5.34362 0.0600009 -0.224552 -0.00372359 0.0601284 0.051617 0.996848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.749 0.316893 30.4929 398.565 0.514582 102.303 +EDGE_SE3:QUAT 784 785 5.20441 0.285658 -0.247576 -0.00830273 0.0486297 0.0237628 0.9985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.097 0.0586906 24.6256 399.032 2.25191 101.643 +EDGE_SE3:QUAT 785 786 5.20415 0.160135 -0.371703 0.00984232 0.0566969 -0.00035278 0.998343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.177 0.060632 28.6699 398.685 -2.92444 102.304 +EDGE_SE3:QUAT 786 787 5.41632 0.247935 -0.265075 0.000718343 0.0401142 0.00453761 0.999185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.1 0.0162966 20.1682 399.356 -0.250265 101.131 +EDGE_SE3:QUAT 787 788 5.35646 0.110047 -0.240483 0.00251509 0.053495 0.0382834 0.997831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.713 0.213406 26.9201 398.864 -1.14417 101.867 +EDGE_SE3:QUAT 788 789 5.3763 0.163994 -0.199547 -0.00403245 0.0491209 0.0419009 0.997905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.166 0.16313 24.8334 399.035 0.803416 101.537 +EDGE_SE3:QUAT 789 790 5.22384 0.118062 -0.251427 -0.00685081 0.0528452 0.0340953 0.997997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.673 0.134559 26.7987 398.87 1.6935 101.883 +EDGE_SE3:QUAT 790 791 5.2674 0.163355 -0.181639 -0.00557813 0.0596589 0.0710811 0.995669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.681 0.427741 30.31 398.594 0.847345 102.033 +EDGE_SE3:QUAT 791 792 5.46235 0.112308 -0.294751 0.0111106 0.0483714 0.049537 0.997538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.893 0.261763 23.9855 399.05 -3.78152 101.403 +EDGE_SE3:QUAT 792 793 5.34053 0.143157 -0.288242 0.00667082 0.0494992 0.0367851 0.998074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.132 0.19761 24.7783 399.018 -2.34255 101.588 +EDGE_SE3:QUAT 793 794 5.39772 0.181356 -0.45949 0.00793615 0.0548542 0.0184269 0.998293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.885 0.148808 27.6163 398.783 -2.55703 102.102 +EDGE_SE3:QUAT 794 795 5.26147 0.0881441 -0.462425 -0.000970901 0.0618082 0.0231203 0.99782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.017 0.154925 31.3201 398.475 0.0169172 102.656 +EDGE_SE3:QUAT 795 796 5.24086 0.0843215 -0.230388 0.00592257 0.0555928 0.0362711 0.997777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.979 0.238961 27.9293 398.767 -2.15094 102.045 +EDGE_SE3:QUAT 796 797 5.4018 0.0630877 -0.438817 -0.0068302 0.0641529 0.0145795 0.99781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.413 0.0594798 32.5993 398.339 1.85045 102.922 +EDGE_SE3:QUAT 797 798 5.18226 0.00183321 -0.282823 -0.00646625 0.0458278 0.034818 0.998321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.758 0.10177 23.1958 399.148 1.61922 101.382 +EDGE_SE3:QUAT 798 799 5.49213 0.318543 -0.236335 -0.00586507 0.0491646 0.0289811 0.998353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.173 0.0965921 24.8772 399.023 1.4728 101.64 +EDGE_SE3:QUAT 799 800 5.19784 0.0269897 -0.132272 -0.00459186 0.0520465 0.0573184 0.996988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.557 0.258059 26.3549 398.923 0.791605 101.598 +EDGE_SE3:QUAT 800 801 5.36766 0.118349 -0.227007 0.00217697 0.0505467 0.0390243 0.997957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.313 0.192498 25.4118 398.986 -1.03104 101.643 +EDGE_SE3:QUAT 801 802 5.29734 0.0321226 -0.301724 -0.00455665 0.0479126 0.0576776 0.997174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.013 0.218524 24.2379 399.086 0.82203 101.299 +EDGE_SE3:QUAT 802 803 5.08873 0.375587 -0.333561 0.00469994 0.0537897 0.0128148 0.998459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.769 0.0954696 27.127 398.838 -1.53228 102.031 +EDGE_SE3:QUAT 803 804 5.26387 0.118944 -0.284624 -0.0012715 0.0593729 0.0211069 0.998012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.627 0.12759 30.0607 398.592 0.138958 102.454 +EDGE_SE3:QUAT 804 805 5.38505 -0.0123196 -0.252434 0.00308334 0.0430783 0.0382659 0.998334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.393 0.141961 21.5776 399.262 -1.24318 101.154 +EDGE_SE3:QUAT 805 806 5.50148 0.270317 -0.370595 0.00183579 0.049961 0.0209687 0.998529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.255 0.105104 25.1659 399.004 -0.750056 101.716 +EDGE_SE3:QUAT 806 807 5.42807 0.0265666 -0.143237 -0.00481383 0.0591961 0.0668384 0.995995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.603 0.397925 30.0406 398.615 0.674234 102.047 +EDGE_SE3:QUAT 807 808 5.35942 0.0292008 -0.322296 -0.000491161 0.0503822 -0.0210161 0.998509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.317 -0.0997567 25.3996 398.987 0.351216 101.746 +EDGE_SE3:QUAT 808 809 5.48797 0.280071 -0.321361 0.00502453 0.0513075 0.0294856 0.998235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.401 0.168503 25.7779 398.947 -1.79003 101.768 +EDGE_SE3:QUAT 809 810 5.19527 0.225186 -0.288108 -0.00892501 0.0563563 0.05501 0.996854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.2 0.266386 28.7194 398.714 2.0614 101.991 +EDGE_SE3:QUAT 810 811 5.42915 -0.103176 -0.377902 0.0116251 0.0440871 0.0174067 0.998808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.451 0.115292 22.0605 399.187 -3.62017 101.368 +EDGE_SE3:QUAT 811 812 5.40434 0.0836267 -0.377622 -0.00300044 0.0504263 0.0244166 0.998425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.333 0.0966818 25.4704 398.982 0.656249 101.741 +EDGE_SE3:QUAT 812 813 5.27955 0.10831 -0.0775811 0.000275865 0.0434214 0.0150282 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.462 0.0527023 21.8476 399.247 -0.209683 101.305 +EDGE_SE3:QUAT 813 814 5.31338 0.157936 -0.192599 -0.00638936 0.0500016 0.0754521 0.995874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.292 0.312083 25.386 399.007 1.1727 101.22 +EDGE_SE3:QUAT 814 815 5.43932 0.049648 -0.189942 0.00384597 0.055059 0.00827978 0.998441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.961 0.0693664 27.802 398.784 -1.23242 102.139 +EDGE_SE3:QUAT 815 816 5.37214 0.170266 -0.11408 0.00125802 0.0512794 0.031799 0.998177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.426 0.158922 25.828 398.954 -0.690194 101.751 +EDGE_SE3:QUAT 816 817 5.43239 0.244191 -0.336115 -0.00188443 0.0539458 -0.0115078 0.998476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.807 -0.0723217 27.2329 398.836 0.680574 102.043 +EDGE_SE3:QUAT 817 818 5.41394 0.182768 -0.465227 -0.0048616 0.0536318 0.0314489 0.998054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.779 0.136675 27.1581 398.845 1.12317 101.948 +EDGE_SE3:QUAT 818 819 5.4727 0.182763 -0.361857 -0.00190751 0.0605686 0.0589703 0.996419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.795 0.38225 30.6473 398.555 -0.115103 102.247 +EDGE_SE3:QUAT 819 820 5.33132 0.0880952 -0.132311 -0.00108263 0.0610986 0.0426613 0.997219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.888 0.283711 30.9285 398.519 -0.174816 102.46 +EDGE_SE3:QUAT 820 821 5.41932 0.0351362 -0.347685 -3.75251e-05 0.0586069 -0.000442049 0.998281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.508 -0.00302584 29.6592 398.626 0.0161049 102.433 +EDGE_SE3:QUAT 821 822 5.38314 0.229323 -0.217536 -0.00136942 0.0535668 0.0359378 0.997916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.755 0.17993 27.0526 398.858 0.0369407 101.899 +EDGE_SE3:QUAT 822 823 5.44748 0.218967 -0.308589 0.000555044 0.0552644 0.00680125 0.998448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.003 0.0413404 27.9266 398.779 -0.237368 102.156 +EDGE_SE3:QUAT 823 824 5.43172 0.209787 -0.450308 0.0058574 0.0466861 0.0144059 0.998789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.821 0.0863504 23.4647 399.121 -1.87829 101.521 +EDGE_SE3:QUAT 824 825 5.373 0.133324 -0.271507 -0.0020781 0.0538398 0.0263956 0.998198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.801 0.127286 27.2117 398.842 0.345332 101.982 +EDGE_SE3:QUAT 825 826 5.46788 0.0849329 -0.229361 0.00414761 0.0483477 0.0338224 0.998249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.017 0.164353 24.2596 399.068 -1.5547 101.528 +EDGE_SE3:QUAT 826 827 5.38079 -0.127509 -0.102887 0.0102025 0.0503986 0.0449038 0.997667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.18 0.258079 25.0898 398.973 -3.48132 101.588 +EDGE_SE3:QUAT 827 828 5.37724 -0.0326756 -0.138603 0.00269985 0.0520249 0.00380268 0.998635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.54 0.03425 26.2538 398.916 -0.842528 101.912 +EDGE_SE3:QUAT 828 829 5.3739 0.035482 -0.321164 -0.0040824 0.0482085 0.0342935 0.99824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.049 0.124118 24.3616 399.068 0.896819 101.532 +EDGE_SE3:QUAT 829 830 5.33084 0.273933 -0.334283 -0.00569688 0.0494429 -0.0124976 0.998683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.172 -0.0861326 24.8858 399.015 1.81814 101.715 +EDGE_SE3:QUAT 830 831 5.52419 0.00794975 -0.227209 0.00248467 0.0522083 0.00755344 0.998605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.564 0.0518141 26.3418 398.909 -0.816282 101.921 +EDGE_SE3:QUAT 831 832 5.42515 0.0714178 -0.478357 -0.00270515 0.0485349 0.0463482 0.997742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.083 0.184746 24.4977 399.063 0.370069 101.451 +EDGE_SE3:QUAT 832 833 5.58756 0.210566 -0.307069 0.00846764 0.0523304 -0.00758225 0.998565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.57 0.0111455 26.4549 398.882 -2.44596 101.955 +EDGE_SE3:QUAT 833 834 5.50835 0.184763 -0.228267 0.00486392 0.053107 0.0373946 0.997877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.636 0.218808 26.6684 398.877 -1.83235 101.844 +EDGE_SE3:QUAT 834 835 5.61127 0.0507605 -0.17027 0.00502727 0.0476894 0.0139554 0.998752 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.951 0.0835033 23.9873 399.085 -1.62871 101.588 +EDGE_SE3:QUAT 835 836 5.48043 0.0209374 -0.418011 -0.000876128 0.0627635 -0.00848646 0.997992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.174 -0.0675922 31.8124 398.425 0.361167 102.787 +EDGE_SE3:QUAT 836 837 5.56699 0.175323 -0.351172 -0.000625129 0.0552287 0.0275754 0.998093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.994 0.149609 27.9026 398.784 -0.106489 102.08 +EDGE_SE3:QUAT 837 838 5.32762 0.11804 -0.350563 -0.00128383 0.0453443 0.0200001 0.99877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.689 0.0684861 22.8436 399.178 0.206612 101.41 +EDGE_SE3:QUAT 838 839 5.42237 0.164304 -0.384447 0.0053902 0.0461342 0.0492697 0.997705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.708 0.213955 23.0229 399.155 -2.05248 101.245 +EDGE_SE3:QUAT 839 840 5.44521 0.162823 -0.328552 0.00158756 0.0486638 0.0740063 0.996068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.03 0.322736 24.3372 399.08 -1.17626 101.101 +EDGE_SE3:QUAT 840 841 5.61253 0.069914 -0.223577 0.00732432 0.0597531 0.0224855 0.997933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.623 0.195342 30.1337 398.564 -2.43378 102.481 +EDGE_SE3:QUAT 841 842 5.39787 0.258225 -0.197657 9.32466e-05 0.0514018 0.0405807 0.997853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.443 0.195338 25.8981 398.952 -0.43124 101.696 +EDGE_SE3:QUAT 842 843 5.43317 -0.085881 -0.210751 0.00138628 0.0537154 0.0488511 0.99736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.742 0.263631 27.0282 398.861 -0.919368 101.789 +EDGE_SE3:QUAT 843 844 5.40771 0.215645 -0.200565 0.0112184 0.0531271 0.0292408 0.998097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.574 0.213337 26.5985 398.846 -3.64164 101.922 +EDGE_SE3:QUAT 844 845 5.52266 0.0229137 -0.387959 0.00324279 0.0588059 0.0295707 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.503 0.207601 29.677 398.622 -1.29675 102.354 +EDGE_SE3:QUAT 845 846 5.49201 0.0676575 -0.366536 0.00597101 0.054765 -0.0120875 0.998408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.93 -0.0297737 27.7129 398.789 -1.6504 102.122 +EDGE_SE3:QUAT 846 847 5.38153 0.0831649 -0.258973 -0.00185734 0.0489835 0.0416787 0.997928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.137 0.17218 24.7069 399.046 0.157825 101.52 +EDGE_SE3:QUAT 847 848 5.35694 -0.0482841 -0.330069 0.00555038 0.064901 0.0539654 0.996416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.41 0.452236 32.6515 398.339 -2.31258 102.669 +EDGE_SE3:QUAT 848 849 5.27639 0.0945423 -0.288511 -0.00382148 0.053917 0.0444678 0.997547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.816 0.2137 27.2906 398.841 0.67629 101.866 +EDGE_SE3:QUAT 849 850 5.44542 0.183225 -0.34732 0.0164519 0.0561509 0.0192287 0.998102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.954 0.211472 28.1723 398.668 -5.1032 102.251 +EDGE_SE3:QUAT 850 851 5.55677 0.286422 -0.438426 -0.00331851 0.054704 0.0110191 0.998436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.924 0.0399901 27.6604 398.8 0.87214 102.11 +EDGE_SE3:QUAT 851 852 5.52507 0.118717 -0.196016 0.00884649 0.0529161 0.0170294 0.998415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.604 0.137861 26.6161 398.862 -2.80886 101.962 +EDGE_SE3:QUAT 852 853 5.46886 0.159076 -0.271589 0.00311374 0.0485693 0.0538857 0.99736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.028 0.244782 24.3161 399.071 -1.43813 101.359 +EDGE_SE3:QUAT 853 854 5.51199 0.217291 -0.299369 0.000902227 0.0664347 0.0193164 0.997603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.798 0.16345 33.7137 398.238 -0.50937 103.096 +EDGE_SE3:QUAT 854 855 5.51543 0.283903 -0.381323 0.0072359 0.0535992 0.0290229 0.998114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.693 0.193215 26.9172 398.845 -2.45509 101.945 +EDGE_SE3:QUAT 855 856 5.65074 -0.0270548 -0.216601 0.00101686 0.0550787 -0.00371787 0.998475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.977 -0.0143363 27.8363 398.786 -0.263377 102.145 +EDGE_SE3:QUAT 856 857 5.30723 0.182254 -0.322114 0.00134915 0.0556734 0.0283936 0.998044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.046 0.16863 28.096 398.766 -0.705159 102.107 +EDGE_SE3:QUAT 857 858 5.5815 0.102338 -0.487154 -0.00322101 0.0490067 0.0275672 0.998413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.148 0.103542 24.7482 399.038 0.698669 101.625 +EDGE_SE3:QUAT 858 859 5.54776 -0.0447337 -0.342395 0.00213215 0.0595285 0.00293252 0.99822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.649 0.0334322 30.1328 398.581 -0.667115 102.511 +EDGE_SE3:QUAT 859 860 5.73325 -0.0703218 -0.298173 -0.000123238 0.053412 0.0196637 0.998379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.735 0.101532 26.9666 398.861 -0.165549 101.977 +EDGE_SE3:QUAT 860 861 5.44636 -0.101466 -0.227333 0.00702601 0.0520606 -0.00804277 0.998587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.54 0.000652698 26.3116 398.9 -2.01243 101.927 +EDGE_SE3:QUAT 861 862 5.46832 0.0034815 -0.48038 0.00669092 0.0538771 0.0313884 0.998032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.734 0.2042 27.0568 398.836 -2.3187 101.949 +EDGE_SE3:QUAT 862 863 5.60754 0.110966 -0.340274 -0.00347209 0.0574549 0.0558497 0.996779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.329 0.315182 29.0988 398.692 0.417632 102.03 +EDGE_SE3:QUAT 863 864 5.6811 0.0430915 -0.330111 -3.42997e-05 0.0622656 0.0343331 0.997469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.078 0.24323 31.5254 398.459 -0.396017 102.627 +EDGE_SE3:QUAT 864 865 5.53086 0.188418 -0.350275 0.00134701 0.0459017 0.00157626 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.754 0.0127174 23.1197 399.157 -0.416012 101.486 +EDGE_SE3:QUAT 865 866 5.48949 0.142582 -0.318214 -0.00362897 0.0474416 0.0387212 0.998117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.951 0.140365 23.9624 399.1 0.725691 101.446 +EDGE_SE3:QUAT 866 867 5.82972 0.149178 -0.298758 0.00142012 0.0613616 0.00242351 0.998112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.945 0.0266905 31.0871 398.493 -0.45018 102.67 +EDGE_SE3:QUAT 867 868 5.57386 0.223666 -0.276354 -0.0021002 0.0600359 0.0262596 0.997849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.734 0.15901 30.4154 398.561 0.323817 102.488 +EDGE_SE3:QUAT 868 869 5.61316 0.0253105 -0.377634 -0.00313552 0.059145 -0.00549513 0.998229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.584 -0.0561714 29.9262 398.598 0.994234 102.477 +EDGE_SE3:QUAT 869 870 5.62345 -0.120347 -0.192941 -0.00218133 0.0630585 0.0323201 0.997484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.226 0.219924 31.986 398.415 0.261254 102.719 +EDGE_SE3:QUAT 870 871 5.69018 0.0424455 -0.410373 -0.00558508 0.0634204 0.0558517 0.996407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.302 0.373128 32.2637 398.399 0.986385 102.561 +EDGE_SE3:QUAT 871 872 5.62336 0.108373 -0.20576 0.00163998 0.0611615 0.0239033 0.99784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.896 0.174827 30.9437 398.508 -0.765488 102.59 +EDGE_SE3:QUAT 872 873 5.63896 0.00598252 -0.294655 -0.00484164 0.0470799 0.0283003 0.998478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.907 0.0897911 23.7905 399.107 1.18559 101.496 +EDGE_SE3:QUAT 873 874 5.44794 0.176577 -0.379727 -0.00586627 0.0632872 0.0204436 0.997769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.273 0.107649 32.1548 398.388 1.49671 102.819 +EDGE_SE3:QUAT 874 875 5.47986 0.15967 -0.190827 -0.000998019 0.0450604 0.00801406 0.998952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.655 0.0247259 22.6948 399.188 0.227563 101.425 +EDGE_SE3:QUAT 875 876 5.61406 -0.0213291 -0.266134 0.00168749 0.056098 0.00800147 0.998392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.122 0.056567 28.3505 398.741 -0.588241 102.22 +EDGE_SE3:QUAT 876 877 5.79605 0.114555 -0.34615 0.00885091 0.0510153 0.0368192 0.99798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.302 0.220623 25.5043 398.95 -3.00215 101.701 +EDGE_SE3:QUAT 877 878 5.55674 0.0988603 -0.207797 -0.0054061 0.0527379 0.0424556 0.997691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.658 0.184939 26.7254 398.884 1.17869 101.803 +EDGE_SE3:QUAT 878 879 5.46382 0.141946 -0.254806 -0.00200706 0.0586097 -0.0152537 0.998162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.497 -0.108981 29.6347 398.627 0.767606 102.408 +EDGE_SE3:QUAT 879 880 5.68799 0.127466 -0.327294 -0.00828348 0.0540674 0.0698771 0.996055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.866 0.327825 27.5479 398.826 1.73872 101.62 +EDGE_SE3:QUAT 880 881 5.78704 0.106964 -0.528972 -0.00276661 0.0592684 0.0332588 0.997684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.614 0.195431 30.0287 398.598 0.446312 102.382 +EDGE_SE3:QUAT 881 882 5.72918 0.138789 -0.156362 -0.0031539 0.0499445 0.0476231 0.997611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.268 0.199611 25.2318 399.008 0.479394 101.54 +EDGE_SE3:QUAT 882 883 5.86222 0.0796744 -0.241965 -0.000574244 0.0647257 0.0461617 0.996835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.483 0.349689 32.7933 398.342 -0.395357 102.753 +EDGE_SE3:QUAT 883 884 5.74574 0.117091 -0.0058916 0.00281409 0.0528257 0.0274165 0.998223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.63 0.155274 26.6057 398.887 -1.11767 101.892 +EDGE_SE3:QUAT 884 885 5.51883 -0.00973307 -0.438069 -0.00133931 0.0572244 0.0393172 0.997586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.288 0.226537 28.9341 398.699 -0.0327259 102.162 +EDGE_SE3:QUAT 885 886 5.60348 0.213426 -0.329835 0.00225129 0.0600489 0.0387635 0.99744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.693 0.269697 30.3088 398.569 -1.11363 102.393 +EDGE_SE3:QUAT 886 887 5.74311 0.13457 -0.423206 0.00235654 0.0475903 0.0517838 0.997521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.917 0.223282 23.8496 399.107 -1.18305 101.317 +EDGE_SE3:QUAT 887 888 5.65981 0.14786 -0.205742 0.00115686 0.0538035 0.0247891 0.998243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.781 0.137528 27.143 398.846 -0.601318 101.981 +EDGE_SE3:QUAT 888 889 5.62041 0.125545 -0.399808 -0.00216952 0.0564995 0.0590728 0.996651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.171 0.330457 28.5549 398.741 0.00413298 101.907 +EDGE_SE3:QUAT 889 890 5.79303 0.153249 -0.341452 0.00238745 0.0586295 0.042382 0.997377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.465 0.280391 29.5567 398.638 -1.18576 102.242 +EDGE_SE3:QUAT 890 891 5.85574 -0.0637915 -0.421095 -0.00279948 0.0605212 0.0298751 0.997716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.814 0.181283 30.6794 398.537 0.487672 102.512 +EDGE_SE3:QUAT 891 892 5.73138 -0.0787459 -0.407888 0.00656107 0.0611048 0.0285687 0.997701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.833 0.23926 30.812 398.505 -2.28227 102.56 +EDGE_SE3:QUAT 892 893 5.60928 0.0926899 -0.382789 0.00490975 0.0538514 -0.0151685 0.998422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.803 -0.0509954 27.2414 398.832 -1.30489 102.039 +EDGE_SE3:QUAT 893 894 5.67846 0.160198 -0.326742 0.000317912 0.0556212 0.049936 0.997202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.025 0.282728 28.0386 398.779 -0.629087 101.929 +EDGE_SE3:QUAT 894 895 5.68276 0.0336129 -0.272 -0.0019628 0.0633607 0.0353766 0.997362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.274 0.246157 32.1364 398.401 0.157855 102.725 +EDGE_SE3:QUAT 895 896 5.67846 -0.0196392 -0.483228 -0.00284755 0.0552106 0.0177323 0.998313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404 0.0812301 27.9256 398.779 0.659667 102.13 +EDGE_SE3:QUAT 896 897 5.70897 -0.0344093 -0.313103 -0.000510783 0.0580541 0.00455084 0.998303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.423 0.0246929 29.3736 398.652 0.101423 102.385 +EDGE_SE3:QUAT 897 898 5.8709 0.0972814 -0.176418 0.00261766 0.0599419 0.00915695 0.998156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.709 0.078 30.334 398.562 -0.88266 102.538 +EDGE_SE3:QUAT 898 899 5.68489 0.113443 -0.288222 -0.00739827 0.0537535 0.0543764 0.997045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.813 0.245212 27.3258 398.836 1.64034 101.78 +EDGE_SE3:QUAT 899 900 5.71728 0.00504936 -0.166699 0.00492759 0.0507343 0.0513808 0.997377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.288 0.264315 25.3762 398.982 -1.97493 101.537 +EDGE_SE3:QUAT 900 901 5.81606 0.130423 -0.307906 -0.000626344 0.0519569 0.0290493 0.998227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.531 0.13925 26.2165 398.924 -0.104769 101.821 +EDGE_SE3:QUAT 901 902 5.58134 0.106567 -0.366241 0.00158405 0.0532923 0.0296976 0.998136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.702 0.162639 26.8615 398.869 -0.776898 101.914 +EDGE_SE3:QUAT 902 903 5.66485 0.0396712 -0.491777 0.00059662 0.0588454 0.0357455 0.997627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.524 0.229715 29.7334 398.624 -0.579535 102.318 +EDGE_SE3:QUAT 903 904 5.78158 -0.0729035 -0.267288 -0.00434442 0.0511207 0.0586004 0.996962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.429 0.255895 25.8713 398.962 0.714923 101.513 +EDGE_SE3:QUAT 904 905 5.71539 0.110967 -0.316183 0.00208303 0.0578531 0.0405094 0.997501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.352 0.259928 29.1702 398.673 -1.06876 102.194 +EDGE_SE3:QUAT 905 906 5.61754 0.00202861 -0.257216 0.00508021 0.058875 0.00896957 0.998212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.528 0.0906042 29.7664 398.608 -1.61136 102.451 +EDGE_SE3:QUAT 906 907 5.66768 0.00672407 -0.43321 0.00757824 0.0501104 -0.0155797 0.998593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.283 -0.0297495 25.3434 398.977 -2.10792 101.772 +EDGE_SE3:QUAT 907 908 5.74752 0.088552 -0.375093 -0.0110055 0.05697 0.0422319 0.997422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.284 0.182602 29.0523 398.666 2.81371 102.181 +EDGE_SE3:QUAT 908 909 5.74854 0.0195906 -0.432354 -0.00170196 0.0602201 0.0172155 0.998035 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.764 0.102656 30.5061 398.55 0.308399 102.543 +EDGE_SE3:QUAT 909 910 5.75807 0.0225051 -0.510702 -0.00259663 0.0548014 0.051329 0.997174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.932 0.26574 27.7061 398.81 0.231583 101.862 +EDGE_SE3:QUAT 910 911 5.89262 0.168562 -0.386208 -0.0055418 0.0597506 -0.00950531 0.998153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.662 -0.099559 30.2156 398.565 1.75562 102.526 +EDGE_SE3:QUAT 911 912 5.8348 0.140481 -0.282375 0.00584853 0.0549697 0.0311919 0.997984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.9 0.206086 27.6375 398.791 -2.07121 102.034 +EDGE_SE3:QUAT 912 913 5.59309 0.202325 -0.398574 0.010588 0.0568013 -0.0202272 0.998124 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.226 -0.0520199 28.8449 398.674 -2.93004 102.29 +EDGE_SE3:QUAT 913 914 5.63077 0.0391913 -0.313469 0.0019617 0.0626027 0.0179124 0.997876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.136 0.142562 31.7034 398.435 -0.795376 102.745 +EDGE_SE3:QUAT 914 915 5.73142 0.0274934 -0.268815 -0.00319402 0.0481979 0.0259103 0.998497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.044 0.0929912 24.3322 399.069 0.71036 101.578 +EDGE_SE3:QUAT 915 916 5.71058 0.154148 -0.443108 -0.000614617 0.0644022 0.0335238 0.997361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.442 0.250255 32.6522 398.35 -0.226164 102.829 +EDGE_SE3:QUAT 916 917 5.87182 0.186107 -0.260194 0.000656172 0.0531524 0.00845386 0.99855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.7 0.0474063 26.8358 398.87 -0.28197 101.989 +EDGE_SE3:QUAT 917 918 5.83543 0.123671 -0.422451 -0.00454384 0.0598015 0.0701971 0.995729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.693 0.430013 30.3386 398.591 0.547899 102.05 +EDGE_SE3:QUAT 918 919 5.63953 0.0833965 -0.361634 0.00496011 0.05362 0.028568 0.99814 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.721 0.178085 26.972 398.851 -1.77254 101.946 +EDGE_SE3:QUAT 919 920 5.74183 0.046585 -0.415589 -0.00316141 0.0543244 -0.00819453 0.998485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.858 -0.0631779 27.4269 398.818 1.02688 102.081 +EDGE_SE3:QUAT 920 921 5.83403 0.0342787 -0.272573 -0.00350199 0.0640688 -0.0152335 0.997823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.376 -0.140397 32.4585 398.358 1.22423 102.889 +EDGE_SE3:QUAT 921 922 5.66737 0.0669562 -0.452664 -0.000201385 0.0505601 0.0302625 0.998262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.339 0.139614 25.4899 398.982 -0.235999 101.711 +EDGE_SE3:QUAT 922 923 5.70358 0.0310954 -0.289324 -0.010557 0.0470059 0.0514513 0.997513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.917 0.156108 23.9616 399.084 2.67973 101.351 +EDGE_SE3:QUAT 923 924 5.61169 0.139257 -0.367081 0.013535 0.0560601 -0.00171075 0.998334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.051 0.0752724 28.3507 398.688 -4.00911 102.279 +EDGE_SE3:QUAT 924 925 5.69891 0.0508799 -0.393864 -0.000528545 0.0499666 0.0422361 0.997857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.256 0.18875 25.1752 399.01 -0.251422 101.58 +EDGE_SE3:QUAT 925 926 5.88813 0.228558 -0.19915 -0.00670069 0.0713999 0.0175076 0.997272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.729 0.107524 36.4097 397.947 1.75057 103.623 +EDGE_SE3:QUAT 926 927 5.88074 0.142328 -0.447172 -0.00654566 0.0556197 0.0357872 0.997789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.072 0.162553 28.2257 398.752 1.56627 102.085 +EDGE_SE3:QUAT 927 928 5.76557 0.178848 -0.369578 0.000793734 0.0532309 0.00582613 0.998565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.711 0.0347841 26.8778 398.867 -0.296116 101.999 +EDGE_SE3:QUAT 928 929 5.70815 0.0326216 -0.244624 0.00238639 0.0620207 0.0149098 0.997961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.041 0.121886 31.403 398.462 -0.884482 102.704 +EDGE_SE3:QUAT 929 930 5.83768 0.00219686 -0.328391 0.00487105 0.0560697 0.0466126 0.997326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.041 0.294557 28.1451 398.755 -1.95289 101.99 +EDGE_SE3:QUAT 930 931 5.90511 -0.0241702 -0.27371 -0.0058719 0.0628409 0.00349468 0.998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.181 -0.0172363 31.8712 398.41 1.70202 102.813 +EDGE_SE3:QUAT 931 932 5.84093 0.0277419 -0.364922 0.00888865 0.0637638 0.0153422 0.997807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.277 0.179055 32.2444 398.356 -2.82411 102.874 +EDGE_SE3:QUAT 932 933 5.80103 0.342445 -0.311277 -0.00779103 0.057187 0.0335245 0.99777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.307 0.151411 29.056 398.675 1.95088 102.235 +EDGE_SE3:QUAT 933 934 5.84555 0.127618 -0.289495 0.00287017 0.0608041 0.00472991 0.998134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.849 0.0519327 30.7901 398.519 -0.907598 102.62 +EDGE_SE3:QUAT 934 935 5.7416 0.256171 -0.276999 0.0157572 0.0664382 0.0134772 0.997575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.65 0.230047 33.5891 398.169 -4.84208 103.173 +EDGE_SE3:QUAT 935 936 5.73812 0.324558 -0.304425 -0.00630069 0.0510356 0.0368938 0.997995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.425 0.14077 25.8634 398.949 1.51395 101.726 +EDGE_SE3:QUAT 936 937 5.90347 0.154624 -0.182696 0.00140061 0.0676363 0.0491968 0.996495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.964 0.422282 34.2428 398.194 -1.04258 102.992 +EDGE_SE3:QUAT 937 938 5.78436 0.244822 -0.315574 -0.00487428 0.057593 0.0397953 0.997535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.364 0.210611 29.212 398.672 1.0113 102.205 +EDGE_SE3:QUAT 938 939 5.91267 -0.00339733 -0.36096 0.00791855 0.0733767 0.0383226 0.996536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.966 0.445761 37.1382 397.854 -2.86698 103.672 +EDGE_SE3:QUAT 939 940 5.6436 0.0739063 -0.545369 -0.000600972 0.0493516 0.00516278 0.998768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.188 0.019649 24.8889 399.026 0.129847 101.717 +EDGE_SE3:QUAT 940 941 6.14703 0.0470746 -0.412763 0.00156279 0.0541014 0.0258134 0.998201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.82 0.146859 27.2877 398.833 -0.734173 101.999 +EDGE_SE3:QUAT 941 942 5.93524 0.180158 -0.368718 1.56322e-05 0.066599 0.00805466 0.997747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.837 0.0657569 33.8208 398.226 -0.10562 103.146 +EDGE_SE3:QUAT 942 943 5.6897 -0.0722077 -0.43154 -0.00303096 0.0621432 0.0550033 0.996546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.066 0.367922 31.5113 398.472 0.249999 102.438 +EDGE_SE3:QUAT 943 944 5.9741 -0.0735058 -0.255266 0.0025999 0.0642353 0.0233348 0.997659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.4 0.195433 32.5312 398.354 -1.05543 102.869 +EDGE_SE3:QUAT 944 945 5.94247 0.207794 -0.351528 -0.00179086 0.0616955 0.0373902 0.997393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.995 0.248077 31.2641 398.486 0.0933479 102.559 +EDGE_SE3:QUAT 945 946 5.81961 0.0534436 -0.343714 0.0030792 0.0680986 0.0129492 0.99759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.09 0.13496 34.5778 398.145 -1.0783 103.28 +EDGE_SE3:QUAT 946 947 5.76548 -0.00733043 -0.535869 0.00276826 0.0541442 0.0500913 0.997272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.785 0.281857 27.201 398.843 -1.34788 101.806 +EDGE_SE3:QUAT 947 948 5.93372 0.160423 -0.245852 -0.00724591 0.0551789 0.035918 0.997804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.009 0.156242 28.0141 398.768 1.77638 102.053 +EDGE_SE3:QUAT 948 949 5.83659 0.190445 -0.278819 -0.00488502 0.0583182 0.0347486 0.997681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.475 0.184682 29.5823 398.637 1.06551 102.302 +EDGE_SE3:QUAT 949 950 5.80575 0.0490006 -0.217435 0.00249905 0.0647837 0.0354253 0.997267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.477 0.290206 32.7774 398.333 -1.17609 102.843 +EDGE_SE3:QUAT 950 951 5.94037 -0.105746 -0.383996 0.00175332 0.06163 0.0102958 0.998044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.983 0.0839603 31.2144 398.481 -0.641431 102.682 +EDGE_SE3:QUAT 951 952 5.93269 0.118407 -0.361279 -0.000195034 0.0562409 0.0430366 0.997489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.128 0.246739 28.3903 398.747 -0.406833 102.046 +EDGE_SE3:QUAT 952 953 5.77817 0.122147 -0.168345 -0.00713184 0.0572715 0.0499653 0.997082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.328 0.255909 29.1223 398.681 1.57369 102.103 +EDGE_SE3:QUAT 953 954 5.87231 0.0449308 -0.325559 0.001801 0.0580636 0.043819 0.997349 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.382 0.280186 29.2747 398.666 -1.02328 102.183 +EDGE_SE3:QUAT 954 955 5.95759 -0.10446 -0.461411 -0.00183394 0.0502518 0.00502031 0.998722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.306 0.012983 25.3546 398.989 0.497863 101.782 +EDGE_SE3:QUAT 955 956 5.78406 0.0738019 -0.441606 0.00260627 0.0660304 -0.0030822 0.997809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.736 -0.00457309 33.5299 398.254 -0.734736 103.1 +EDGE_SE3:QUAT 956 957 5.95271 0.145364 -0.482912 -0.00384884 0.0513609 0.0580097 0.996987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.458 0.25807 25.9767 398.954 0.570428 101.535 +EDGE_SE3:QUAT 957 958 5.98294 0.0981044 -0.314154 -0.00483138 0.0587249 0.0230723 0.997996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.534 0.113754 29.7751 398.615 1.17796 102.402 +EDGE_SE3:QUAT 958 959 5.7759 0.128567 -0.228232 0.00585243 0.0668411 0.00735613 0.997719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.855 0.106108 33.9193 398.205 -1.82804 103.177 +EDGE_SE3:QUAT 959 960 5.89375 0.0637932 -0.254576 0.00282593 0.0545015 0.00466035 0.998499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.887 0.0423994 27.5275 398.81 -0.890166 102.1 +EDGE_SE3:QUAT 960 961 5.9505 -0.0616201 -0.446693 -0.0112302 0.0592019 0.0146495 0.998075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.582 0.0185786 30.0619 398.558 3.17313 102.51 +EDGE_SE3:QUAT 961 962 5.8297 0.085111 -0.342315 -0.000122619 0.0692807 -0.0127078 0.997516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.32 -0.113234 35.2238 398.082 0.20122 103.399 +EDGE_SE3:QUAT 962 963 5.8165 0.221306 -0.185925 -0.00318361 0.0563851 0.00446574 0.998394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.168 0.0057907 28.5172 398.725 0.899065 102.252 +EDGE_SE3:QUAT 963 964 6.00393 -0.00931952 -0.462183 -0.0041135 0.0637516 0.0290201 0.997535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.352 0.186499 32.384 398.373 0.870949 102.811 +EDGE_SE3:QUAT 964 965 5.86789 0.0261723 -0.306497 9.51124e-06 0.0557261 0.0213402 0.998218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.067 0.12098 28.1564 398.761 -0.231058 102.15 +EDGE_SE3:QUAT 965 966 5.98908 0.0378531 -0.256978 -0.00613245 0.0639962 0.0382771 0.997197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.403 0.243483 32.5652 398.356 1.35684 102.784 +EDGE_SE3:QUAT 966 967 5.93551 0.266178 -0.358432 -0.0012386 0.05191 0.0262635 0.998306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.528 0.121919 26.2051 398.925 0.105886 101.835 +EDGE_SE3:QUAT 967 968 5.78028 0.228768 -0.360943 -0.00226398 0.0592611 0.0511997 0.996926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.6 0.313713 29.9971 398.61 0.0930941 102.225 +EDGE_SE3:QUAT 968 969 5.7936 0.0885477 -0.277645 -0.00721563 0.0559928 0.0244834 0.998105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.12 0.0954707 28.4 398.73 1.88451 102.184 +EDGE_SE3:QUAT 969 970 5.91996 0.0673377 -0.349883 8.26986e-05 0.0591739 0.0709903 0.99572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.53 0.451435 29.807 398.636 -0.830743 101.954 +EDGE_SE3:QUAT 970 971 5.89389 0.168067 -0.444025 0.00154506 0.0524781 0.0104502 0.998566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.602 0.0613808 26.4811 398.899 -0.565998 101.934 +EDGE_SE3:QUAT 971 972 5.84825 0.149212 -0.287992 0.00552338 0.0519332 0.0336862 0.998067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.473 0.19534 26.069 398.922 -1.98411 101.785 +EDGE_SE3:QUAT 972 973 6.02934 0.0713096 -0.27386 0.0109846 0.0675059 0.0260692 0.997318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.866 0.302369 34.0885 398.156 -3.58853 103.179 +EDGE_SE3:QUAT 973 974 5.91278 0.131277 -0.509767 0.00248986 0.0589565 0.0230193 0.997992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.541 0.162513 29.7891 398.613 -0.99957 102.405 +EDGE_SE3:QUAT 974 975 5.832 0.0566081 -0.246129 0.00260815 0.0598089 -0.0127552 0.998125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.699 -0.0658116 30.2988 398.567 -0.629902 102.523 +EDGE_SE3:QUAT 975 976 5.78135 0.0543821 -0.423562 -0.000227474 0.0625563 -0.0351902 0.997421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.123 -0.253459 31.669 398.445 0.485692 102.646 +EDGE_SE3:QUAT 976 977 5.87459 0.140453 -0.474698 -0.000656299 0.0634979 0.0108263 0.997923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.3 0.0752417 32.203 398.388 0.0646842 102.85 +EDGE_SE3:QUAT 977 978 5.90999 0.0765201 -0.34204 -0.00287617 0.0540177 0.0423116 0.997639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.826 0.208382 27.3172 398.838 0.416361 101.888 +EDGE_SE3:QUAT 978 979 5.91373 -0.0464542 -0.424729 -0.00252478 0.0594886 0.0277249 0.997841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.649 0.162669 30.1386 398.586 0.435986 102.434 +EDGE_SE3:QUAT 979 980 5.92006 -0.0370302 -0.394517 0.000840414 0.0629892 0.000473053 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.215 0.00954562 31.9366 398.413 -0.255198 102.816 +EDGE_SE3:QUAT 980 981 5.67788 0.160756 -0.482692 -0.00752506 0.0652778 0.0102165 0.997786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.599 0.022766 33.1756 398.277 2.10681 103.039 +EDGE_SE3:QUAT 981 982 5.81624 -0.0320606 -0.355133 0.00593274 0.0538632 -0.00265849 0.998527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.791 0.0214604 27.2161 398.829 -1.73906 102.062 +EDGE_SE3:QUAT 982 983 6.01713 0.210474 -0.204899 0.00920212 0.0652491 0.0195193 0.997636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.516 0.220969 32.9873 398.28 -2.97124 102.994 +EDGE_SE3:QUAT 983 984 5.92896 0.0675336 -0.57383 -0.00556992 0.0630684 0.0420158 0.997109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.245 0.267277 32.0724 398.408 1.1515 102.665 +EDGE_SE3:QUAT 984 985 6.11662 0.020977 -0.424975 0.00282426 0.0566361 0.0218465 0.998152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.185 0.145531 28.587 398.719 -1.07758 102.219 +EDGE_SE3:QUAT 985 986 5.87066 0.0469223 -0.506174 -0.00202582 0.0476061 0.0112924 0.9988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.966 0.0360994 24.0043 399.092 0.499929 101.588 +EDGE_SE3:QUAT 986 987 5.91167 0.103836 -0.465919 0.000172622 0.0622715 0.00435265 0.99805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.095 0.0321658 31.562 398.449 -0.102701 102.749 +EDGE_SE3:QUAT 987 988 5.8007 0.0691662 -0.407599 -0.0112427 0.0664594 0.00899658 0.997685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.784 -0.0145178 33.8079 398.194 3.22154 103.176 +EDGE_SE3:QUAT 988 989 5.92943 0.0156208 -0.199829 -0.0087783 0.0575784 0.0292992 0.997872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.362 0.121554 29.2627 398.65 2.28852 102.299 +EDGE_SE3:QUAT 989 990 5.98538 0.110079 -0.419333 0.00919379 0.0575252 0.0318312 0.997794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.232 0.248911 28.8846 398.665 -3.0864 102.241 +EDGE_SE3:QUAT 990 991 5.99323 0.060736 -0.552609 -0.00393587 0.0574321 0.0500244 0.997088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.333 0.277029 29.1057 398.688 0.620358 102.094 +EDGE_SE3:QUAT 991 992 5.87864 0.00983747 -0.301448 0.00192129 0.0669781 0.0205527 0.997541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.887 0.18418 33.9824 398.21 -0.828874 103.142 +EDGE_SE3:QUAT 992 993 6.05482 0.0756201 -0.41822 -0.00236041 0.0641754 0.0585157 0.996219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.394 0.424194 32.5373 398.376 -0.0117136 102.577 +EDGE_SE3:QUAT 993 994 6.03533 0.0059417 -0.304103 0.00199719 0.0514519 -0.0031087 0.998669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.466 -0.00367619 25.9696 398.94 -0.564238 101.871 +EDGE_SE3:QUAT 994 995 6.03443 0.12901 -0.252569 0.00358413 0.0599911 0.0570031 0.996564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.632 0.394844 30.1546 398.586 -1.7204 102.2 +EDGE_SE3:QUAT 995 996 5.96137 0.0238147 -0.302607 0.00374966 0.0550077 0.0377747 0.997764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.916 0.229824 27.6713 398.798 -1.51637 101.987 +EDGE_SE3:QUAT 996 997 5.95767 0.0792133 -0.469595 0.000496488 0.0600466 0.0399103 0.997397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.709 0.265885 30.3478 398.57 -0.604977 102.388 +EDGE_SE3:QUAT 997 998 5.78988 0.181554 -0.349835 -0.00263323 0.0566381 0.0113073 0.998327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.209 0.0495575 28.655 398.715 0.660821 102.261 +EDGE_SE3:QUAT 998 999 5.99736 0.0144268 -0.270316 -0.00457504 0.0638413 0.0169667 0.997805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.364 0.0932416 32.4212 398.364 1.15317 102.876 +EDGE_SE3:QUAT 999 1000 6.02616 0.16531 -0.61513 0.00336567 0.0634427 0.00945119 0.997935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.278 0.0943142 32.15 398.388 -1.11283 102.848 +EDGE_SE3:QUAT 1000 1001 5.87236 0.0343077 -0.196024 0.00110793 0.0671821 0.0380474 0.997014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.906 0.323156 34.0542 398.209 -0.810161 103.053 +EDGE_SE3:QUAT 1001 1002 6.00823 0.187838 -0.18849 0.00295446 0.0641303 0.01335 0.997848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.392 0.122483 32.5012 398.355 -1.03895 102.901 +EDGE_SE3:QUAT 1002 1003 5.94887 0.0268525 -0.230844 -0.00779169 0.0565909 0.0421893 0.997475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.223 0.199229 28.7726 398.705 1.86096 102.123 +EDGE_SE3:QUAT 1003 1004 5.80156 0.0651958 -0.4677 0.00175828 0.0628237 0.0054234 0.998008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.184 0.0519495 31.8436 398.421 -0.586723 102.798 +EDGE_SE3:QUAT 1004 1005 6.0407 0.140861 -0.372566 0.00469562 0.051453 -0.00827538 0.99863 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.465 -0.0133251 25.9887 398.934 -1.31698 101.872 +EDGE_SE3:QUAT 1005 1006 5.87842 -0.0265365 -0.626934 -0.000128165 0.0587166 0.0536635 0.996831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.49 0.336016 29.6397 398.641 -0.56542 102.142 +EDGE_SE3:QUAT 1006 1007 5.83783 0.0109809 -0.340803 0.00309069 0.061006 0.0232542 0.997862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.861 0.179424 30.8429 398.515 -1.18847 102.579 +EDGE_SE3:QUAT 1007 1008 6.03981 0.051088 -0.538192 0.00559111 0.0575499 0.0480939 0.997168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.247 0.322839 28.8783 398.688 -2.19519 102.094 +EDGE_SE3:QUAT 1008 1009 5.86934 0.0524011 -0.357282 0.00448458 0.0563574 0.0210752 0.998178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.132 0.149972 28.423 398.729 -1.56237 102.201 +EDGE_SE3:QUAT 1009 1010 6.0856 -0.0641573 -0.228599 0.000939129 0.0592876 -0.00239329 0.998238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.614 -0.00906942 30.0134 398.594 -0.252139 102.49 +EDGE_SE3:QUAT 1010 1011 5.91605 0.0942708 -0.400208 0.00363102 0.0598414 0.0226451 0.997944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.671 0.172464 30.2325 398.57 -1.33786 102.482 +EDGE_SE3:QUAT 1011 1012 5.90871 0.0513194 -0.363139 0.00343571 0.0606022 0.00389982 0.998148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.815 0.0499665 30.6854 398.528 -1.06598 102.604 +EDGE_SE3:QUAT 1012 1013 6.16339 -0.00735077 -0.317404 0.00348865 0.0621506 0.00258556 0.998057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.069 0.0432009 31.4938 398.452 -1.0667 102.742 +EDGE_SE3:QUAT 1013 1014 6.10255 0.0940275 -0.635988 0.00267748 0.0498 0.019043 0.998574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.231 0.100309 25.0773 399.009 -0.98182 101.712 +EDGE_SE3:QUAT 1014 1015 6.27194 0.102547 -0.211161 0.00513339 0.0553756 0.0319847 0.99794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.965 0.209125 27.857 398.776 -1.86878 102.06 +EDGE_SE3:QUAT 1015 1016 6.10932 0.0610938 -0.221518 0.00231899 0.0600107 0.00955158 0.998149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.72 0.0787298 30.3706 398.559 -0.798491 102.543 +EDGE_SE3:QUAT 1016 1017 5.97724 0.0958543 -0.326323 -0.0103232 0.0613161 0.0207695 0.997849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.938 0.0710331 31.1859 398.462 2.82492 102.669 +EDGE_SE3:QUAT 1017 1018 6.18252 -0.0466147 -0.480401 0.00278446 0.0680212 0.0233793 0.997406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.064 0.220596 34.5085 398.154 -1.12426 103.23 +EDGE_SE3:QUAT 1018 1019 5.86558 -0.0521078 -0.200907 -0.0100573 0.0615129 0.0478637 0.996907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.007 0.264338 31.4026 398.461 2.42844 102.511 +EDGE_SE3:QUAT 1019 1020 6.00306 -0.0442583 -0.379921 -0.0036748 0.0640377 -0.00581565 0.997924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.381 -0.0709545 32.4687 398.357 1.16126 102.91 +EDGE_SE3:QUAT 1020 1021 5.94107 0.0144093 -0.24275 -0.00448082 0.0593112 0.0591091 0.996478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.623 0.351651 30.0919 398.605 0.662032 102.153 +EDGE_SE3:QUAT 1021 1022 6.08892 0.231953 -0.176065 -0.00382183 0.0607555 -0.00896159 0.998105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.833 -0.0869734 30.7499 398.521 1.23931 102.61 +EDGE_SE3:QUAT 1022 1023 6.03162 0.180877 -0.421028 0.00126535 0.0631637 -0.0103549 0.997949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.245 -0.0665442 32.0329 398.404 -0.251799 102.822 +EDGE_SE3:QUAT 1023 1024 6.00148 0.129429 -0.372576 -0.00406575 0.0557848 0.043788 0.997474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.089 0.22429 28.2594 398.758 0.741065 102.02 +EDGE_SE3:QUAT 1024 1025 6.05035 0.174562 -0.415445 -0.00678941 0.0541158 0.0296454 0.998071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.85 0.118308 27.4399 398.815 1.71313 102.007 +EDGE_SE3:QUAT 1025 1026 5.99791 0.128957 -0.452235 0.000168181 0.0559586 -0.00163014 0.998432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.106 -0.00826787 28.2888 398.747 -0.0325596 102.215 +EDGE_SE3:QUAT 1026 1027 6.13104 0.0557912 -0.494837 0.0124 0.0596188 0.0171884 0.997996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.552 0.194176 30.0365 398.54 -3.88181 102.517 +EDGE_SE3:QUAT 1027 1028 6.19718 0.00188284 -0.0350639 -0.00354424 0.0636862 -0.0188798 0.997785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.306 -0.166072 32.2464 398.379 1.27998 102.84 +EDGE_SE3:QUAT 1028 1029 6.04898 -0.149089 -0.43079 0.000936575 0.0560164 0.0348886 0.99782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.094 0.205144 28.2656 398.753 -0.654051 102.092 +EDGE_SE3:QUAT 1029 1030 6.07776 0.213207 -0.460237 -0.00295369 0.051794 0.027264 0.998281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.518 0.116671 26.1739 398.927 0.607518 101.826 +EDGE_SE3:QUAT 1030 1031 5.96802 -0.00522613 -0.457727 -0.00405076 0.0582877 0.0133548 0.998202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.461 0.0563607 29.5225 398.636 1.05595 102.396 +EDGE_SE3:QUAT 1031 1032 6.22543 -0.182285 -0.205716 0.00576171 0.0679305 -0.00621825 0.997654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.071 -0.00664282 34.5416 398.144 -1.62857 103.291 +EDGE_SE3:QUAT 1032 1033 5.92141 -0.0835197 -0.488146 -0.010659 0.0552789 0.0300421 0.997962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.015 0.102886 28.1119 398.742 2.85397 102.124 +EDGE_SE3:QUAT 1033 1034 5.95662 0.131831 -0.471892 0.00458064 0.0585949 -0.00403581 0.998263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.501 0.00505216 29.6636 398.62 -1.31694 102.438 +EDGE_SE3:QUAT 1034 1035 6.16636 -0.0920027 -0.24997 -0.00124148 0.0695834 0.0356886 0.996937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.368 0.307623 35.3746 398.074 -0.0975307 103.316 +EDGE_SE3:QUAT 1035 1036 6.14762 -0.0920677 -0.371614 0.00369287 0.0596343 -0.0170529 0.998068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.674 -0.0860881 30.2232 398.574 -0.903924 102.498 +EDGE_SE3:QUAT 1036 1037 5.83265 0.192045 -0.309486 0.00787887 0.0601478 0.0234968 0.997882 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.676 0.207974 30.3239 398.543 -2.61153 102.511 +EDGE_SE3:QUAT 1037 1038 6.23999 0.0602393 -0.31331 0.00611162 0.0568804 0.0458212 0.99731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.145 0.305565 28.5315 398.715 -2.31982 102.063 +EDGE_SE3:QUAT 1038 1039 6.05938 -0.0866351 -0.498915 -0.00213985 0.0622086 0.0415067 0.997197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.079 0.279138 31.5349 398.462 0.144896 102.573 +EDGE_SE3:QUAT 1039 1040 6.08795 -0.0407294 -0.313913 0.0113661 0.0657452 -0.00469913 0.997761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.646 0.0499873 33.4054 398.231 -3.31332 103.111 +EDGE_SE3:QUAT 1040 1041 6.17816 0.0865528 -0.32067 0.00738674 0.0599833 0.039505 0.99739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.617 0.306482 30.1425 398.564 -2.64904 102.381 +EDGE_SE3:QUAT 1041 1042 6.0294 0.0910283 -0.423507 -0.00230948 0.0649713 0.0182676 0.997717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.555 0.124199 32.9876 398.312 0.461184 102.968 +EDGE_SE3:QUAT 1042 1043 6.08031 0.174105 -0.491993 0.00424879 0.0625501 0.00998379 0.997983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.123 0.102015 31.6776 398.432 -1.38031 102.767 +EDGE_SE3:QUAT 1043 1044 5.92115 -0.0679761 -0.327502 -0.00124578 0.0615033 0.0253463 0.997784 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.967 0.166858 31.1642 398.491 0.0737623 102.618 +EDGE_SE3:QUAT 1044 1045 6.11748 -0.139381 -0.265619 0.00464475 0.0602257 0.00696228 0.99815 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.746 0.0780103 30.4766 398.544 -1.46033 102.57 +EDGE_SE3:QUAT 1045 1046 6.07842 0.14253 -0.318501 -0.000198049 0.0668884 0.0394746 0.996979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.865 0.322258 33.9289 398.225 -0.43895 103.017 +EDGE_SE3:QUAT 1046 1047 6.25197 -0.00353764 -0.211457 0.00609739 0.0665336 0.0425841 0.996856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.717 0.389278 33.5629 398.242 -2.3442 102.944 +EDGE_SE3:QUAT 1047 1048 6.14763 0.0153264 -0.29719 -0.00498858 0.0741588 0.0373679 0.996534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.273 0.33565 37.8734 397.803 0.961278 103.799 +EDGE_SE3:QUAT 1048 1049 6.26747 0.0405014 -0.23807 -0.00304174 0.0568581 -0.0141513 0.998277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.225 -0.102832 28.721 398.706 1.05914 102.267 +EDGE_SE3:QUAT 1049 1050 6.19465 0.0756759 -0.388615 0.00844252 0.0596605 0.0226824 0.997925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.595 0.203383 30.068 398.564 -2.7682 102.475 +EDGE_SE3:QUAT 1050 1051 5.98696 -0.187737 -0.236546 -0.00816615 0.0638196 0.0151875 0.997812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.354 0.0533542 32.4398 398.35 2.24071 102.897 +EDGE_SE3:QUAT 1051 1052 6.21685 0.0684367 -0.35136 -0.000712724 0.0646028 0.0368478 0.99723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.474 0.276498 32.7532 398.341 -0.238916 102.823 +EDGE_SE3:QUAT 1052 1053 5.82945 -0.131538 -0.359098 -0.00128754 0.0586723 -0.00323315 0.998271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.516 -0.0289069 29.6901 398.623 0.419072 102.438 +EDGE_SE3:QUAT 1053 1054 6.108 0.0588155 -0.362254 -0.00171163 0.0634007 0.058695 0.996259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.256 0.419196 32.1099 398.417 -0.198902 102.5 +EDGE_SE3:QUAT 1054 1055 6.03233 -0.0878955 -0.43975 0.00128071 0.0565658 -0.00584679 0.998381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.197 -0.026046 28.6063 398.72 -0.317716 102.262 +EDGE_SE3:QUAT 1055 1056 6.09999 -0.159129 -0.463801 -0.00129045 0.0600697 0.0352062 0.997572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.731 0.223603 30.4111 398.564 -0.0197079 102.432 +EDGE_SE3:QUAT 1056 1057 6.14705 -0.0628454 -0.38181 0.011948 0.0667402 0.00643869 0.997678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.783 0.14576 33.8417 398.179 -3.62397 103.197 +EDGE_SE3:QUAT 1057 1058 6.01423 0.11765 -0.295349 0.00870285 0.0683056 0.0046656 0.997616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.102 0.110059 34.6886 398.113 -2.63913 103.335 +EDGE_SE3:QUAT 1058 1059 6.27957 0.0556596 -0.31728 0.00584205 0.0603771 0.0188507 0.997981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.744 0.16526 30.4968 398.537 -1.95321 102.549 +EDGE_SE3:QUAT 1059 1060 6.06892 0.092216 -0.491312 0.00798312 0.0558069 0.00358202 0.998403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.052 0.0701745 28.1903 398.736 -2.41417 102.219 +EDGE_SE3:QUAT 1060 1061 6.12134 -0.0398637 -0.421935 0.000499187 0.0580965 0.0276256 0.997929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.417 0.173447 29.3649 398.655 -0.455465 102.31 +EDGE_SE3:QUAT 1061 1062 6.09705 0.167517 -0.460076 0.00509272 0.068505 -0.00424638 0.997629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.175 0.00457095 34.8351 398.115 -1.4547 103.346 +EDGE_SE3:QUAT 1062 1063 6.19134 0.0928044 -0.500595 0.00369522 0.0543005 0.0130928 0.998432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.847 0.0925756 27.3977 398.819 -1.23698 102.068 +EDGE_SE3:QUAT 1063 1064 6.00901 -0.0938813 -0.257377 -0.000991351 0.0635369 0.0318281 0.997471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.299 0.228231 32.2115 398.392 -0.0889025 102.762 +EDGE_SE3:QUAT 1064 1065 6.13156 0.137904 -0.402413 -0.00936601 0.0615047 0.0158435 0.997937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.964 0.0439866 31.248 398.459 2.59726 102.694 +EDGE_SE3:QUAT 1065 1066 5.8166 -0.0438778 -0.317794 0.00188872 0.0661135 -0.0334709 0.997249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.748 -0.254197 33.5732 398.259 -0.142919 102.994 +EDGE_SE3:QUAT 1066 1067 6.1669 0.0253997 -0.260424 0.00533229 0.0571451 -0.00954008 0.998306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.282 -0.0226692 28.9309 398.685 -1.48197 102.314 +EDGE_SE3:QUAT 1067 1068 6.09435 0.22418 -0.244341 0.000838161 0.0510008 0.00997222 0.998648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.403 0.0519292 25.7267 398.96 -0.348039 101.827 +EDGE_SE3:QUAT 1068 1069 6.03226 -0.0692829 -0.487135 0.00417027 0.0655813 0.0112082 0.997776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.638 0.120196 33.2559 398.277 -1.37593 103.044 +EDGE_SE3:QUAT 1069 1070 6.21386 -0.0629814 -0.417564 -0.00164037 0.0626156 0.0170537 0.997891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.154 0.110788 31.7511 398.432 0.284631 102.754 +EDGE_SE3:QUAT 1070 1071 6.16485 -0.104516 -0.265045 -0.00261757 0.0665887 0.0145213 0.997671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.839 0.0979738 33.8349 398.225 0.594263 103.135 +EDGE_SE3:QUAT 1071 1072 6.05964 -0.0833047 -0.390707 -0.000970857 0.0633093 -0.0103704 0.99794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.265 -0.0832732 32.094 398.398 0.412624 102.833 +EDGE_SE3:QUAT 1072 1073 6.07877 -0.0476411 -0.302659 0.00152693 0.059743 0.00281961 0.998209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.684 0.0287893 30.2455 398.572 -0.48599 102.529 +EDGE_SE3:QUAT 1073 1074 6.0445 -0.00762603 -0.495496 0.00862778 0.0591482 0.0142132 0.998111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.532 0.148137 29.8546 398.583 -2.72571 102.47 +EDGE_SE3:QUAT 1074 1075 6.12225 0.368408 -0.592146 0.000519004 0.0604189 0.0132252 0.998085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.79 0.0919092 30.59 398.541 -0.306385 102.569 +EDGE_SE3:QUAT 1075 1076 6.05755 -0.021068 -0.485975 0.000151932 0.0631569 -0.00680588 0.99798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.243 -0.0486671 32.0236 398.405 0.0363216 102.826 +EDGE_SE3:QUAT 1076 1077 6.31811 0.0947494 -0.306213 0.000836814 0.0557663 0.00142723 0.998442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.077 0.0133295 28.1885 398.756 -0.264315 102.2 +EDGE_SE3:QUAT 1077 1078 6.15222 0.112098 -0.523338 0.00519982 0.0578619 0.018365 0.998142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.357 0.145756 29.203 398.657 -1.74998 102.337 +EDGE_SE3:QUAT 1078 1079 6.17755 0.12819 -0.189973 0.000166029 0.0580167 0.00436373 0.998306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.416 0.0279401 29.3524 398.654 -0.0977652 102.382 +EDGE_SE3:QUAT 1079 1080 5.95207 0.0939997 -0.368303 -0.00679469 0.0605502 0.0503644 0.996871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.839 0.293486 30.8092 398.53 1.43841 102.374 +EDGE_SE3:QUAT 1080 1081 6.05785 0.0426549 -0.326202 -0.00472657 0.0590442 -0.00286835 0.99824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.564 -0.0499215 29.8765 398.599 1.43761 102.475 +EDGE_SE3:QUAT 1081 1082 6.20024 -0.206181 -0.499325 -0.0022265 0.05976 -0.000852824 0.99821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.686 -0.0207093 30.2559 398.57 0.671545 102.532 +EDGE_SE3:QUAT 1082 1083 6.24174 0.152607 -0.390138 -0.00692359 0.060883 0.0479537 0.996968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.892 0.279568 30.9822 398.512 1.50167 102.427 +EDGE_SE3:QUAT 1083 1084 6.06745 0.08815 -0.402558 0.000948461 0.0470786 0.016022 0.998762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.894 0.0693449 23.7079 399.115 -0.429466 101.536 +EDGE_SE3:QUAT 1084 1085 6.18171 0.17784 -0.444196 -0.00346489 0.065504 0.0162138 0.997715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.65 0.101425 33.277 398.281 0.827631 103.029 +EDGE_SE3:QUAT 1085 1086 6.2606 0.147161 -0.343331 0.00520941 0.0608194 0.0124529 0.998058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.83 0.120232 30.7611 398.515 -1.69217 102.609 +EDGE_SE3:QUAT 1086 1087 6.00922 0.0565105 -0.400682 -0.00983958 0.0591244 0.0276844 0.997818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.599 0.112002 30.0751 398.571 2.61316 102.446 +EDGE_SE3:QUAT 1087 1088 6.01097 0.00313886 -0.305999 0.0109082 0.0632056 -0.00625265 0.997921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.218 0.0338466 32.0883 398.365 -3.16375 102.872 +EDGE_SE3:QUAT 1088 1089 6.16575 -0.171466 -0.550936 0.00292871 0.0558256 0.011708 0.998368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.075 0.0848088 28.1946 398.753 -0.997026 102.191 +EDGE_SE3:QUAT 1089 1090 6.21322 -0.00849605 -0.355218 0.00405225 0.05849 -0.00920506 0.998237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.49 -0.0308022 29.6193 398.626 -1.1022 102.422 +EDGE_SE3:QUAT 1090 1091 6.26951 -0.0628921 -0.299126 0.00603581 0.0584328 0.0164599 0.998137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.441 0.142079 29.4977 398.628 -1.97883 102.394 +EDGE_SE3:QUAT 1091 1092 6.28048 0.148534 -0.239882 0.00307108 0.0568433 -0.000593061 0.998378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.235 0.016128 28.7469 398.705 -0.907248 102.29 +EDGE_SE3:QUAT 1092 1093 6.02017 0.0976359 -0.377826 -0.00209798 0.0598225 0.0220164 0.997964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.701 0.130027 30.3049 398.57 0.372593 102.49 +EDGE_SE3:QUAT 1093 1094 5.97986 0.0143573 -0.433581 0.000182796 0.0690146 0.0541694 0.996144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.22 0.473816 34.9852 398.124 -0.757227 103.077 +EDGE_SE3:QUAT 1094 1095 6.15037 0.136784 -0.300618 -0.00630141 0.0555202 0.033122 0.997888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.056 0.148225 28.1633 398.757 1.52267 102.093 +EDGE_SE3:QUAT 1095 1096 6.17229 0.0309696 -0.408303 -0.00304409 0.0626592 0.0152974 0.997913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.164 0.0882363 31.7872 398.427 0.722259 102.768 +EDGE_SE3:QUAT 1096 1097 6.2309 -0.140674 -0.511553 -0.00378723 0.0684212 -0.00785706 0.997618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.151 -0.0981642 34.757 398.125 1.22329 103.325 +EDGE_SE3:QUAT 1097 1098 6.00354 -0.119569 -0.219026 -0.00410422 0.0594337 -0.0194435 0.998034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.608 -0.152829 30.0263 398.587 1.44072 102.462 +EDGE_SE3:QUAT 1098 1099 5.96052 -0.00606136 -0.365239 -0.00514227 0.0676143 0.00234704 0.997696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.011 -0.0212006 34.3618 398.163 1.49463 103.259 +EDGE_SE3:QUAT 1099 1100 6.25167 -0.011181 -0.436577 0.000286033 0.0652179 0.0249406 0.997559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.584 0.19667 33.0761 398.304 -0.392104 102.955 +EDGE_SE3:QUAT 1100 1101 6.28251 0.060292 -0.286956 0.0113803 0.0566308 -0.00720507 0.998304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.17 0.0302684 28.6828 398.677 -3.30768 102.309 +EDGE_SE3:QUAT 1101 1102 6.10196 -0.10118 -0.358981 -0.0121035 0.058752 0.0469073 0.997096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.566 0.219346 30.0267 398.577 3.07296 102.301 +EDGE_SE3:QUAT 1102 1103 6.21236 -0.047097 -0.391111 -0.00379637 0.0558186 0.0105684 0.998378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.087 0.0364505 28.2382 398.749 1.0167 102.2 +EDGE_SE3:QUAT 1103 1104 6.14272 0.210213 -0.293225 -0.00135763 0.0702861 0.00190314 0.997524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.511 0.00594626 35.7607 398.023 0.377082 103.518 +EDGE_SE3:QUAT 1104 1105 6.20722 -0.0358492 -0.386077 0.000123202 0.0622355 -0.00974409 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.089 -0.0682751 31.5422 398.451 0.0784912 102.738 +EDGE_SE3:QUAT 1105 1106 6.21492 -0.0181741 -0.468509 -0.00291825 0.0560234 -0.0117678 0.998356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.104 -0.0856436 28.2967 398.744 0.994911 102.207 +EDGE_SE3:QUAT 1106 1107 6.24165 -0.0238348 -0.372464 -0.00153355 0.0599031 0.00241128 0.9982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.711 0.00537905 30.3337 398.564 0.428311 102.543 +EDGE_SE3:QUAT 1107 1108 6.21019 0.0794247 -0.351371 -0.00109733 0.0539252 -0.00202254 0.998542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.81 -0.0173071 27.2378 398.837 0.347734 102.056 +EDGE_SE3:QUAT 1108 1109 5.93823 -0.00466762 -0.501215 -0.010512 0.0600149 0.0201798 0.997938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.726 0.0616139 30.5089 398.524 2.89367 102.559 +EDGE_SE3:QUAT 1109 1110 6.17681 -0.0820368 -0.49288 6.03669e-05 0.0664805 -0.00773659 0.997758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.816 -0.0623462 33.7593 398.233 0.0789412 103.135 +EDGE_SE3:QUAT 1110 1111 6.29545 0.0712638 -0.411115 0.0183334 0.0569691 0.00809903 0.998175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.087 0.164466 28.7068 398.606 -5.54215 102.379 +EDGE_SE3:QUAT 1111 1112 6.06504 0.0138377 -0.485242 -0.00130182 0.0718148 0.0297893 0.996972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.794 0.271942 36.5588 397.945 -0.0135173 103.584 +EDGE_SE3:QUAT 1112 1113 6.17025 0.0210747 -0.366295 0.0023479 0.0632367 0.0304545 0.997531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.224 0.239483 31.992 398.408 -1.06255 102.736 +EDGE_SE3:QUAT 1113 1114 6.1543 0.16621 -0.242877 0.00140407 0.0594133 -0.013764 0.998138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.635 -0.0794505 30.0841 398.588 -0.261468 102.483 +EDGE_SE3:QUAT 1114 1115 6.22605 -0.095196 -0.470942 0.00828641 0.0652261 0.0026904 0.997832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.563 0.0838759 33.088 398.279 -2.49173 103.04 +EDGE_SE3:QUAT 1115 1116 6.01358 0.0878971 -0.424228 -0.00867023 0.0630183 0.00587793 0.997957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.2 -0.0202486 31.9812 398.388 2.5042 102.841 +EDGE_SE3:QUAT 1116 1117 6.16229 0.22305 -0.31995 -0.00211456 0.0658456 0.0207002 0.997613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.707 0.14868 33.4427 398.267 0.370282 103.04 +EDGE_SE3:QUAT 1117 1118 6.16712 0.149935 -0.312976 -0.00748318 0.0658939 0.0282459 0.997399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.729 0.16861 33.5617 398.248 1.86901 103.035 +EDGE_SE3:QUAT 1118 1119 6.34942 0.103401 -0.406601 -0.000114345 0.0599804 0.0341674 0.997615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.709 0.223797 30.3406 398.569 -0.35694 102.428 +EDGE_SE3:QUAT 1119 1120 6.08571 0.0943472 -0.265715 0.00581894 0.0609506 -0.00332236 0.998118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.87 0.0179573 30.8867 398.504 -1.69049 102.644 +EDGE_SE3:QUAT 1120 1121 6.00073 -0.0804251 -0.178711 -0.0122738 0.0595402 0.0628389 0.99617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.711 0.331641 30.5134 398.546 2.93523 102.202 +EDGE_SE3:QUAT 1121 1122 6.06097 -0.0730442 -0.528845 -0.00252246 0.0663004 0.0189038 0.997617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.788 0.133216 33.6854 398.242 0.51207 103.092 +EDGE_SE3:QUAT 1122 1123 6.27635 0.0225442 -0.330146 0.0078732 0.0646191 0.00734978 0.997852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.451 0.115156 32.7468 398.313 -2.42632 102.973 +EDGE_SE3:QUAT 1123 1124 6.20388 -0.123736 -0.320419 0.0127631 0.0640963 -0.00487835 0.99785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.349 0.0581211 32.5483 398.307 -3.72892 102.967 +EDGE_SE3:QUAT 1124 1125 6.19488 0.0489028 -0.40507 -0.0122791 0.0705148 0.0188441 0.997257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.546 0.0697646 36.0115 397.963 3.38784 103.568 +EDGE_SE3:QUAT 1125 1126 6.34134 0.0211631 -0.488231 -0.00742608 0.0639962 0.0130704 0.997837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.383 0.0432866 32.517 398.344 2.04607 102.914 +EDGE_SE3:QUAT 1126 1127 6.27149 -0.00500805 -0.2324 0.000906307 0.0592374 0.0463536 0.997167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.569 0.30213 29.8987 398.613 -0.794693 102.259 +EDGE_SE3:QUAT 1127 1128 6.05908 0.0801083 -0.328133 -0.00550652 0.0657229 0.0260714 0.997482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.695 0.165172 33.4335 398.265 1.31047 103.018 +EDGE_SE3:QUAT 1128 1129 6.06045 0.0970754 -0.257414 0.00554315 0.0566984 0.00890181 0.998336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.193 0.0874184 28.6371 398.707 -1.74598 102.273 +EDGE_SE3:QUAT 1129 1130 6.19519 0.023938 -0.465982 0.0031513 0.0630113 -0.00234364 0.998005 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.216 0.00584175 31.9526 398.409 -0.907748 102.821 +EDGE_SE3:QUAT 1130 1131 6.2437 0.00818919 -0.282187 -0.000816363 0.0601252 0.0139699 0.998093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.747 0.0868534 30.4484 398.555 0.0826487 102.543 +EDGE_SE3:QUAT 1131 1132 6.17458 -0.157841 -0.456966 0.00317152 0.0542551 0.0465956 0.997434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.801 0.266871 27.2609 398.836 -1.43215 101.849 +EDGE_SE3:QUAT 1132 1133 5.97333 0.128973 -0.364609 0.00116724 0.0685592 0.0262983 0.9973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.17 0.236356 34.8082 398.127 -0.684397 103.268 +EDGE_SE3:QUAT 1133 1134 6.29684 0.00526453 -0.371747 0.00642181 0.0637596 0.00138984 0.997944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.326 0.0577156 32.3317 398.362 -1.92313 102.897 +EDGE_SE3:QUAT 1134 1135 6.33641 -0.158932 -0.206777 -0.00406005 0.066087 0.0543503 0.996324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.747 0.405636 33.6007 398.268 0.526132 102.815 +EDGE_SE3:QUAT 1135 1136 6.15569 0.0989295 -0.218852 0.00114304 0.0621688 -0.014478 0.99796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.079 -0.094398 31.5137 398.455 -0.16867 102.721 +EDGE_SE3:QUAT 1136 1137 6.19086 -0.290265 -0.400818 0.0115381 0.0629505 -6.81703e-06 0.99795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.154 0.083674 31.9127 398.375 -3.42586 102.851 +EDGE_SE3:QUAT 1137 1138 6.10112 0.125422 -0.421247 0.00272873 0.0730707 0.0109423 0.997263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.031 0.131727 37.2046 397.864 -0.955879 103.794 +EDGE_SE3:QUAT 1138 1139 6.28191 -0.137981 -0.375466 -0.00171819 0.0623166 0.0246188 0.997751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.103 0.162977 31.5951 398.449 0.219118 102.696 +EDGE_SE3:QUAT 1139 1140 6.18316 0.0500493 -0.324958 -0.00698731 0.0594754 0.022994 0.99794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.652 0.102111 30.1947 398.57 1.81645 102.478 +EDGE_SE3:QUAT 1140 1141 6.08349 0.136814 -0.497156 -0.000132083 0.0596165 0.0114115 0.998156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.665 0.0733086 30.1801 398.579 -0.09043 102.505 +EDGE_SE3:QUAT 1141 1142 6.155 0.0205256 -0.330061 -0.000262478 0.0636932 -0.0125224 0.997891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.331 -0.0950752 32.2971 398.379 0.228905 102.863 +EDGE_SE3:QUAT 1142 1143 6.28604 0.025346 -0.421007 -0.0115445 0.0603663 0.0565928 0.996504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.834 0.303531 30.8888 398.51 2.78052 102.338 +EDGE_SE3:QUAT 1143 1144 6.26062 0.0205431 -0.677658 0.00335029 0.0629113 -0.0193631 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.207 -0.116389 31.9258 398.415 -0.763973 102.778 +EDGE_SE3:QUAT 1144 1145 6.24365 -0.0324574 -0.262743 -0.00275223 0.0635007 0.00490236 0.997966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.301 0.0160615 32.2112 398.385 0.758164 102.863 +EDGE_SE3:QUAT 1145 1146 6.20747 -0.0339152 -0.392379 0.000753028 0.0593145 -0.0146313 0.998132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.618 -0.0891111 30.027 398.594 -0.0583375 102.471 +EDGE_SE3:QUAT 1146 1147 6.17383 -0.0545486 -0.330068 0.00301099 0.0528062 0.00445176 0.99859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.647 0.0402144 26.6537 398.882 -0.942171 101.971 +EDGE_SE3:QUAT 1147 1148 6.19562 -0.0312521 -0.508851 -0.00359505 0.0637854 0.025111 0.997641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.356 0.161194 32.3898 398.371 0.764078 102.833 +EDGE_SE3:QUAT 1148 1149 6.2634 -0.0914435 -0.49194 -0.00197867 0.0632503 0.0297504 0.997552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.258 0.203912 32.0834 398.404 0.230846 102.752 +EDGE_SE3:QUAT 1149 1150 6.20794 0.00706315 -0.366789 0.00130412 0.0580415 0.0196355 0.99812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.41 0.129283 29.3393 398.655 -0.605809 102.344 +EDGE_SE3:QUAT 1150 1151 6.3853 0.0766322 -0.371624 -0.00374072 0.0575618 0.0257603 0.998003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.354 0.132068 29.1599 398.673 0.829056 102.288 +EDGE_SE3:QUAT 1151 1152 6.36965 0.00317052 -0.340421 0.00325579 0.0656128 0.00441055 0.99783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.656 0.0597524 33.2967 398.275 -1.02048 103.058 +EDGE_SE3:QUAT 1152 1153 6.25122 0.119082 -0.489597 0.00587111 0.0700697 0.0115817 0.997458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.436 0.153305 35.5957 398.029 -1.89079 103.485 +EDGE_SE3:QUAT 1153 1154 6.38591 0.0431815 -0.249205 0.0101289 0.0643248 0.00847307 0.997842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.377 0.139444 32.5735 398.318 -3.10935 102.954 +EDGE_SE3:QUAT 1154 1155 6.22207 -0.126374 -0.551195 0.00179023 0.0700785 0.0192168 0.997355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.455 0.188398 35.615 398.039 -0.782197 103.455 +EDGE_SE3:QUAT 1155 1156 6.24973 0.0357949 -0.346418 0.00433806 0.0538708 -0.0132632 0.99845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.805 -0.044333 27.2423 398.833 -1.15434 102.043 +EDGE_SE3:QUAT 1156 1157 6.28222 0.0285707 -0.466702 -0.00046911 0.0598039 -0.00125005 0.998209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.696 -0.0113738 30.2797 398.569 0.153687 102.534 +EDGE_SE3:QUAT 1157 1158 6.02883 -0.0220242 -0.272902 0.00448299 0.0670632 0.0106194 0.997682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.898 0.122856 34.0314 398.198 -1.4633 103.187 +EDGE_SE3:QUAT 1158 1159 6.25064 0.0633914 -0.346644 0.00244337 0.0695823 -0.0224127 0.997321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.382 -0.179733 35.4069 398.065 -0.431911 103.4 +EDGE_SE3:QUAT 1159 1160 6.22868 -0.0403906 -0.411585 -0.00903606 0.0604282 0.0278601 0.997743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.808 0.124918 30.7388 398.514 2.36497 102.551 +EDGE_SE3:QUAT 1160 1161 6.0705 -0.0717024 -0.375346 3.86871e-05 0.0523158 -0.0133736 0.998541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.583 -0.0664829 26.4063 398.906 0.123392 101.916 +EDGE_SE3:QUAT 1161 1162 6.29081 -0.069955 -0.449193 0.00151279 0.0589924 -0.0124928 0.998179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.569 -0.0694382 29.8665 398.608 -0.309157 102.451 +EDGE_SE3:QUAT 1162 1163 6.14631 -0.0120103 -0.47997 0.00551582 0.0694692 0.028018 0.997175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.292 0.29253 35.2023 398.073 -1.99931 103.347 +EDGE_SE3:QUAT 1163 1164 6.22764 -3.65271e-05 -0.550282 -0.00357547 0.0689212 0.000708191 0.997615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.253 -0.0229877 35.0425 398.096 1.05031 103.384 +EDGE_SE3:QUAT 1164 1165 6.2428 -0.0654257 -0.421962 -0.00687854 0.0608067 0.012 0.998054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.853 0.0335451 30.8476 398.506 1.90513 102.627 +EDGE_SE3:QUAT 1165 1166 6.2161 -0.155607 -0.382093 -0.000504344 0.0710296 -0.00172399 0.997473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.651 -0.0203094 36.1503 397.982 0.172173 103.593 +EDGE_SE3:QUAT 1166 1167 6.15893 -0.0574 -0.40431 -0.00378501 0.0635692 -0.0118369 0.9979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.294 -0.115335 32.2061 398.382 1.26623 102.854 +EDGE_SE3:QUAT 1167 1168 6.05773 -0.168017 -0.413493 0.00336053 0.0541532 -0.0186586 0.998353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.848 -0.079742 27.3869 398.824 -0.80633 102.045 +EDGE_SE3:QUAT 1168 1169 6.28452 0.000196641 -0.238558 -0.00413728 0.0556437 0.00446184 0.998432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.056 -0.000538109 28.1366 398.756 1.18372 102.195 +EDGE_SE3:QUAT 1169 1170 6.58885 -0.295857 -0.378598 0.00861204 0.0666999 0.0199669 0.997536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.775 0.229062 33.7505 398.207 -2.80515 103.127 +EDGE_SE3:QUAT 1170 1171 6.3906 -0.0581844 -0.399454 0.00658646 0.0631913 -0.00382156 0.997972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.237 0.0200721 32.0565 398.389 -1.90985 102.847 +EDGE_SE3:QUAT 1171 1172 6.15073 0.102358 -0.410398 0.000563413 0.0606167 -0.0148846 0.99805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.825 -0.0962295 30.701 398.532 0.00429319 102.582 +EDGE_SE3:QUAT 1172 1173 6.16127 -0.146017 -0.499986 0.00563674 0.058458 -0.00288286 0.99827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.475 0.0192832 29.5911 398.623 -1.644 102.43 +EDGE_SE3:QUAT 1173 1174 6.22705 0.0784242 -0.488882 0.00241846 0.0610762 0.0253379 0.997809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.875 0.189373 30.8832 398.513 -1.01322 102.575 +EDGE_SE3:QUAT 1174 1175 6.14964 0.0735096 -0.220936 0.0054888 0.055877 -0.0113763 0.998358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.093 -0.0305795 28.2815 398.741 -1.51158 102.209 +EDGE_SE3:QUAT 1175 1176 6.38982 0.0183722 -0.435402 0.00166115 0.0632824 0.0214427 0.997764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.248 0.16926 32.053 398.402 -0.750439 102.792 +EDGE_SE3:QUAT 1176 1177 6.52476 0.0590775 -0.171495 0.00658323 0.0698247 -0.0111069 0.997476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.424 -0.0451415 35.5578 398.036 -1.80495 103.477 +EDGE_SE3:QUAT 1177 1178 6.22519 0.00334483 -0.524122 -0.0114444 0.0590072 0.00464997 0.998181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.528 -0.04705 29.896 398.567 3.35008 102.507 +EDGE_SE3:QUAT 1178 1179 5.98156 -0.188664 -0.281838 0.0113619 0.0595352 -0.0115327 0.998095 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.627 0.00209027 30.2159 398.541 -3.24646 102.546 +EDGE_SE3:QUAT 1179 1180 6.12504 0.0176742 -0.511712 0.00468672 0.0713767 0.0109355 0.997378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.692 0.142481 36.2959 397.959 -1.53308 103.618 +EDGE_SE3:QUAT 1180 1181 6.10667 -0.0374723 -0.241947 0.00306085 0.0590597 -0.00171501 0.998248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.576 0.00956577 29.8969 398.602 -0.890717 102.474 +EDGE_SE3:QUAT 1181 1182 6.35836 -0.0447324 -0.440683 2.67927e-05 0.0617572 -0.0263969 0.997742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.001 -0.18405 31.275 398.48 0.301896 102.632 +EDGE_SE3:QUAT 1182 1183 6.31991 0.0903055 -0.108557 -0.00120471 0.0646922 -0.00994553 0.997855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.499 -0.0853931 32.8147 398.327 0.479092 102.961 +EDGE_SE3:QUAT 1183 1184 6.3725 0.181198 -0.36497 0.0031431 0.0574966 -0.0156631 0.998218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.341 -0.0743776 29.1081 398.675 -0.762691 102.322 +EDGE_SE3:QUAT 1184 1185 6.1966 0.201242 -0.518595 0.00248992 0.0603126 -0.0142076 0.998075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.78 -0.0775566 30.5606 398.544 -0.57686 102.562 +EDGE_SE3:QUAT 1185 1186 6.23127 -0.0799887 -0.438554 0.00666086 0.0574693 0.0186622 0.998151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.284 0.154967 28.9809 398.671 -2.18685 102.306 +EDGE_SE3:QUAT 1186 1187 6.14199 -0.0961718 -0.446934 0.00478632 0.0595314 0.00808973 0.998182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.634 0.0847126 30.1117 398.577 -1.5147 102.508 +EDGE_SE3:QUAT 1187 1188 6.20196 -0.128109 -0.216675 0.00115069 0.0557662 -0.00313412 0.998438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.078 -0.0106149 28.1913 398.756 -0.308941 102.2 +EDGE_SE3:QUAT 1188 1189 6.46824 -0.0118163 -0.309085 0.000680613 0.0595029 -0.025499 0.997902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.643 -0.160521 30.1163 398.588 0.0871171 102.442 +EDGE_SE3:QUAT 1189 1190 6.21507 -0.071789 -0.293747 -0.00140408 0.0625283 0.0106014 0.997986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.139 0.0658896 31.7028 398.436 0.291265 102.764 +EDGE_SE3:QUAT 1190 1191 6.3815 0.011158 -0.191186 0.0034287 0.0636105 -0.00675165 0.997946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.32 -0.0249042 32.2739 398.378 -0.936603 102.873 +EDGE_SE3:QUAT 1191 1192 6.14022 -0.0361197 -0.317708 0.000904324 0.0616177 0.00759651 0.998071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.985 0.0592049 31.2166 398.482 -0.357579 102.686 +EDGE_SE3:QUAT 1192 1193 6.21883 0.0924226 -0.388814 0.000106834 0.0561009 -0.0112289 0.998362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.126 -0.0638645 28.3596 398.742 0.0889862 102.214 +EDGE_SE3:QUAT 1193 1194 6.2813 -0.0791019 -0.302846 -0.0049458 0.0567491 0.00891501 0.998336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.222 0.0209414 28.7222 398.704 1.37462 102.282 +EDGE_SE3:QUAT 1194 1195 6.23938 -0.0764255 -0.319361 -0.00152742 0.0650353 0.0208538 0.997664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.564 0.150404 33.0114 398.31 0.197109 102.962 +EDGE_SE3:QUAT 1195 1196 6.25058 -0.199206 -0.369816 -0.00503672 0.065214 0.0359627 0.99721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.608 0.24349 33.1722 398.297 1.05166 102.907 +EDGE_SE3:QUAT 1196 1197 6.26815 -0.176915 -0.460459 -0.00304723 0.0650165 0.0357765 0.997238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.563 0.254952 33.024 398.314 0.464707 102.879 +EDGE_SE3:QUAT 1197 1198 6.15318 0.00500709 -0.408395 0.00964175 0.0603543 0.00277108 0.998127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.739 0.0847459 30.546 398.516 -2.89723 102.607 +EDGE_SE3:QUAT 1198 1199 6.24575 0.052209 -0.510219 0.00827885 0.0645817 0.013261 0.99779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.428 0.162903 32.6902 398.316 -2.619 102.954 +EDGE_SE3:QUAT 1199 1200 6.26576 -0.0804633 -0.345597 0.00270828 0.0728282 -0.0174813 0.997188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.002 -0.147404 37.1198 397.878 -0.564627 103.755 +EDGE_SE3:QUAT 1200 1201 6.2058 0.00716553 -0.407173 -0.00611176 0.0575517 -0.00752908 0.998295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.32 -0.0850805 29.081 398.666 1.90089 102.347 +EDGE_SE3:QUAT 1201 1202 6.21133 -0.199235 -0.226973 0.00179012 0.0711895 -0.0415795 0.996594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.668 -0.372864 36.2228 397.988 0.0230296 103.434 +EDGE_SE3:QUAT 1202 1203 6.21438 0.0122662 -0.380782 0.00242133 0.0645387 0.00328167 0.997907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.473 0.0432127 32.7398 398.332 -0.758631 102.958 +EDGE_SE3:QUAT 1203 1204 6.21195 -0.0819153 -0.444214 0.00887268 0.058284 -0.0176133 0.998105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.455 -0.0511987 29.5796 398.616 -2.44247 102.408 +EDGE_SE3:QUAT 1204 1205 6.16872 -0.12651 -0.42569 -0.00813164 0.062689 0.041119 0.997153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.191 0.239609 31.9398 398.413 1.92605 102.657 +EDGE_SE3:QUAT 1205 1206 6.21633 0.111715 -0.359401 0.00382225 0.0582682 -0.0109918 0.998233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.457 -0.0431129 29.5064 398.637 -1.01435 102.399 +EDGE_SE3:QUAT 1206 1207 6.32873 0.109302 -0.395666 0.00573723 0.0533933 -0.00645681 0.998536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.729 0.000415608 26.9865 398.849 -1.64226 102.023 +EDGE_SE3:QUAT 1207 1208 6.29206 -0.212852 -0.281398 0.00271982 0.0518055 -0.0213465 0.998425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.519 -0.0890178 26.1728 398.925 -0.596975 101.855 +EDGE_SE3:QUAT 1208 1209 6.45017 -0.034892 -0.593871 -0.0025071 0.0696185 -6.88263e-05 0.997571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.384 -0.0213457 35.4076 398.059 0.743589 103.452 +EDGE_SE3:QUAT 1209 1210 6.32709 -0.133107 -0.460409 -0.00118536 0.0651974 -0.000480785 0.997872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.591 -0.0127496 33.0891 398.299 0.357629 103.02 +EDGE_SE3:QUAT 1210 1211 6.21435 -0.0563002 -0.193585 -0.00597791 0.05926 0.0128251 0.998142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.61 0.0422864 30.0406 398.584 1.63226 102.487 +EDGE_SE3:QUAT 1211 1212 6.40085 -0.126828 -0.394095 0.00436425 0.0638855 -0.0121054 0.997874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.369 -0.0584429 32.4329 398.362 -1.14921 102.892 +EDGE_SE3:QUAT 1212 1213 6.29461 -0.0960924 -0.113984 -0.0012746 0.0678278 0.00558032 0.997681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.058 0.037029 34.4707 398.159 0.306757 103.27 +EDGE_SE3:QUAT 1213 1214 6.03313 0.0836024 -0.478308 0.00101058 0.05984 -0.00181894 0.998206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.702 -0.00503814 30.2999 398.567 -0.279651 102.538 +EDGE_SE3:QUAT 1214 1215 6.36117 -0.0184892 -0.427555 0.00236257 0.0533272 0.000755751 0.998574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.724 0.0178943 26.9298 398.861 -0.711386 102.012 +EDGE_SE3:QUAT 1215 1216 6.19065 -0.130134 -0.622243 0.00751978 0.0636127 -0.0173907 0.997795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.323 -0.074049 32.3343 398.363 -2.02302 102.868 +EDGE_SE3:QUAT 1216 1217 6.19733 -0.102603 -0.313682 0.00210475 0.066974 0.0115255 0.997686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.894 0.111439 33.9994 398.206 -0.769369 103.174 +EDGE_SE3:QUAT 1217 1218 6.17407 -0.126553 -0.298197 0.001246 0.0667592 -0.0172864 0.997619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.866 -0.131846 33.911 398.219 -0.152293 103.139 +EDGE_SE3:QUAT 1218 1219 6.31511 -0.126804 -0.414715 -0.000277646 0.0661701 0.0176714 0.997652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.758 0.13993 33.5915 398.251 -0.138012 103.079 +EDGE_SE3:QUAT 1219 1220 6.39377 -0.288752 -0.304232 -0.00205242 0.0603431 -0.0308313 0.997699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.753 -0.218789 30.4925 398.551 0.964758 102.478 +EDGE_SE3:QUAT 1220 1221 6.39289 -0.0663798 -0.305302 -0.00753543 0.0683531 -0.0131469 0.997546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.101 -0.173185 34.6716 398.119 2.40211 103.313 +EDGE_SE3:QUAT 1221 1222 6.28966 -0.00119897 -0.270048 0.00939617 0.0624069 -0.0207347 0.997791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.121 -0.081039 31.7417 398.414 -2.54511 102.759 +EDGE_SE3:QUAT 1222 1223 6.17122 0.0132848 -0.391997 -0.00128898 0.0579929 0.00208935 0.998314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.413 0.00440374 29.3426 398.654 0.360206 102.382 +EDGE_SE3:QUAT 1223 1224 6.29206 -0.0198421 -0.189114 0.00141312 0.0600782 0.0128745 0.99811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.732 0.0946362 30.4062 398.557 -0.567381 102.54 +EDGE_SE3:QUAT 1224 1225 6.28551 0.118613 -0.317331 0.00259544 0.0601551 0.00393922 0.998178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.747 0.0438652 30.4553 398.551 -0.816537 102.564 +EDGE_SE3:QUAT 1225 1226 6.35893 0.0761398 -0.14686 -0.00124647 0.0569332 0.0105505 0.998321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.253 0.0545225 28.7977 398.703 0.255838 102.284 +EDGE_SE3:QUAT 1226 1227 6.29498 -0.0588479 -0.4579 -0.00796249 0.0558846 0.00169644 0.998404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.072 -0.0401853 28.2572 398.732 2.35141 102.229 +EDGE_SE3:QUAT 1227 1228 6.03972 -0.00553889 -0.459341 0.00688146 0.0674252 -0.00513191 0.997687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.974 0.0116837 34.2762 398.167 -1.97511 103.247 +EDGE_SE3:QUAT 1228 1229 6.05532 -0.0844357 -0.300037 0.00638665 0.0651918 -0.0248514 0.997543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.603 -0.146041 33.1672 398.289 -1.58924 102.979 +EDGE_SE3:QUAT 1229 1230 6.3632 -0.0759518 -0.388078 -0.0105034 0.0566499 0.00980361 0.998291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.184 -0.00940019 28.7052 398.682 3.01858 102.301 +EDGE_SE3:QUAT 1230 1231 6.22883 0.0639962 -0.388497 0.00479529 0.0619353 -0.0136809 0.997975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.043 -0.0621844 31.4233 398.458 -1.26354 102.713 +EDGE_SE3:QUAT 1231 1232 6.15602 0.048115 -0.397565 -0.00880135 0.0589523 0.00549097 0.998207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.54 -0.0239634 29.8657 398.586 2.555 102.485 +EDGE_SE3:QUAT 1232 1233 6.17968 -0.0168155 -0.406422 0.00979837 0.0605997 -0.0154338 0.997995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.814 -0.0361665 30.7794 398.5 -2.7337 102.618 +EDGE_SE3:QUAT 1233 1234 6.31784 0.019186 -0.279467 0.00371989 0.0641429 -0.0115366 0.997867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.413 -0.0595022 32.5615 398.35 -0.964211 102.915 +EDGE_SE3:QUAT 1234 1235 6.18515 -0.0802051 -0.231245 -0.00242646 0.0743333 -0.00553783 0.997215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.288 -0.0783813 37.8867 397.789 0.793758 103.939 +EDGE_SE3:QUAT 1235 1236 6.18542 -0.182362 -0.404059 0.00122968 0.0729745 -0.00375043 0.997326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.027 -0.0260232 37.1801 397.869 -0.312947 103.796 +EDGE_SE3:QUAT 1236 1237 6.22582 -0.0130983 -0.631928 -0.000522388 0.0650931 0.00544378 0.997864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.574 0.0383864 33.0359 398.305 0.0881123 103.007 +EDGE_SE3:QUAT 1237 1238 6.22747 0.0813933 -0.36263 0.00639879 0.06646 -0.00296521 0.997764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.801 0.0257429 33.7607 398.221 -1.86061 103.152 +EDGE_SE3:QUAT 1238 1239 6.13728 -0.245842 -0.469497 -0.00352006 0.0593499 0.023405 0.997957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.63 0.127378 30.0806 398.589 0.781556 102.448 +EDGE_SE3:QUAT 1239 1240 6.43442 0.0421073 -0.445315 -0.0011165 0.0610743 -0.0224704 0.99788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.887 -0.161019 30.9094 398.512 0.592897 102.59 +EDGE_SE3:QUAT 1240 1241 6.22238 0.00147875 -0.419885 -0.000137355 0.0534278 0.00636289 0.998551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.74 0.0323127 26.9825 398.858 -0.0245317 102.014 +EDGE_SE3:QUAT 1241 1242 6.3993 0.0521169 -0.274175 0.00379377 0.0590378 -0.0325212 0.997719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.583 -0.18246 29.9302 398.606 -0.761489 102.372 +EDGE_SE3:QUAT 1242 1243 6.33238 0.0638039 -0.303752 -0.00234279 0.0596945 0.0268296 0.997853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.681 0.159224 30.2423 398.577 0.391052 102.456 +EDGE_SE3:QUAT 1243 1244 6.2392 -0.35763 -0.230175 0.0142457 0.0684966 -0.0499846 0.996297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.234 -0.321988 35.1854 398.066 -3.57986 103.196 +EDGE_SE3:QUAT 1244 1245 6.19106 -0.00378847 -0.528655 0.00348367 0.0672003 0.0421523 0.996843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.873 0.374455 33.9856 398.211 -1.56738 103.014 +EDGE_SE3:QUAT 1245 1246 6.29399 0.0514532 -0.393738 0.00380327 0.0658786 -0.0379989 0.997097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.717 -0.27428 33.4916 398.268 -0.655989 102.948 +EDGE_SE3:QUAT 1246 1247 6.33133 -0.108199 -0.230448 -0.00424179 0.0585259 -0.00911136 0.998235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.479 -0.0850387 29.59 398.626 1.36325 102.42 +EDGE_SE3:QUAT 1247 1248 6.18836 -0.026359 -0.419592 0.00380014 0.0701621 -0.0157968 0.997403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.493 -0.111618 35.7236 398.027 -0.918347 103.488 +EDGE_SE3:QUAT 1248 1249 6.25769 -0.0970828 -0.322165 0.00770498 0.0704833 -0.0217451 0.997246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.559 -0.134804 35.9528 397.995 -1.99546 103.52 +EDGE_SE3:QUAT 1249 1250 6.2899 -0.116221 -0.353315 0.00399119 0.0612355 -0.0228211 0.997854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.933 -0.129064 31.0658 398.497 -0.920173 102.616 +EDGE_SE3:QUAT 1250 1251 6.12708 -0.158827 -0.517068 0.00441087 0.0659696 0.0139209 0.997715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.7 0.144918 33.4474 398.257 -1.48163 103.073 +EDGE_SE3:QUAT 1251 1252 6.27115 -0.0676382 -0.360185 0.00252701 0.0634699 0.00148348 0.997979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.292 0.0294896 32.1849 398.387 -0.768073 102.861 +EDGE_SE3:QUAT 1252 1253 6.1248 -0.147014 -0.489388 0.00461184 0.0596759 -0.00113657 0.998207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.668 0.0238963 30.2163 398.569 -1.35797 102.53 +EDGE_SE3:QUAT 1253 1254 6.53703 0.0602544 -0.456811 0.00274825 0.0630366 -0.00194698 0.998006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.221 0.00579838 31.9647 398.408 -0.79279 102.822 +EDGE_SE3:QUAT 1254 1255 6.33501 0.016488 -0.398003 -0.000564718 0.0571732 -0.0159368 0.998237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.283 -0.0987579 28.9041 398.694 0.342437 102.287 +EDGE_SE3:QUAT 1255 1256 6.14413 -0.18662 -0.551819 -0.0024405 0.062145 0.0176712 0.997908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.078 0.107741 31.515 398.455 0.516448 102.712 +EDGE_SE3:QUAT 1256 1257 6.55898 0.051227 -0.377206 0.00974202 0.05989 -0.01894 0.997978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.707 -0.0582725 30.4284 398.535 -2.67952 102.547 +EDGE_SE3:QUAT 1257 1258 6.21983 -0.122294 -0.398302 0.00203878 0.0635348 0.0194188 0.997789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.29 0.158417 32.1845 398.388 -0.83904 102.824 +EDGE_SE3:QUAT 1258 1259 6.45607 0.0608365 -0.660542 -0.00546194 0.0693607 -0.0346703 0.996974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.255 -0.34911 35.1088 398.085 2.06989 103.288 +EDGE_SE3:QUAT 1259 1260 6.20101 -0.203207 -0.363907 0.00316082 0.0661114 -0.0123155 0.997731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.754 -0.0745201 33.5874 398.249 -0.784154 103.096 +EDGE_SE3:QUAT 1260 1261 6.35532 0.104986 -0.260977 -0.00119774 0.0667899 -0.0151821 0.997651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.863 -0.133702 33.9038 398.218 0.546073 103.146 +EDGE_SE3:QUAT 1261 1262 6.3133 -0.0197678 -0.442567 -0.00263699 0.0632265 -0.0131531 0.997909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.241 -0.115487 32.0331 398.401 0.940572 102.818 +EDGE_SE3:QUAT 1262 1263 6.20818 -0.255142 -0.269164 -0.00037435 0.0523311 -0.0011805 0.998629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.587 -0.00805826 26.418 398.905 0.123431 101.935 +EDGE_SE3:QUAT 1263 1264 6.3877 -0.0229373 -0.413832 0.00235237 0.0648484 0.0221842 0.997646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.509 0.188473 32.8583 398.322 -0.97005 102.932 +EDGE_SE3:QUAT 1264 1265 6.05697 -0.00198107 -0.408921 0.00378459 0.0641809 -0.027016 0.997565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.424 -0.176417 32.6006 398.351 -0.795397 102.86 +EDGE_SE3:QUAT 1265 1266 6.28397 -0.153569 -0.664427 0.00266208 0.0587675 0.00154475 0.998267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.529 0.0274793 29.7396 398.617 -0.808885 102.448 +EDGE_SE3:QUAT 1266 1267 6.24397 -0.120219 -0.435927 -0.000504604 0.0699719 0.0145166 0.997443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.45 0.126655 35.5913 398.043 -0.0405104 103.464 +EDGE_SE3:QUAT 1267 1268 6.30926 -0.150044 -0.303697 0.000510734 0.0554311 -0.014932 0.998351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.028 -0.080596 28.0151 398.772 0.00685035 102.151 +EDGE_SE3:QUAT 1268 1269 6.29611 -0.00343735 -0.285131 -0.00190634 0.0651349 -0.00713103 0.997849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.575 -0.0699527 33.0465 398.303 0.653342 103.008 +EDGE_SE3:QUAT 1269 1270 6.22615 0.10802 -0.349673 -0.00100408 0.061417 -0.0117163 0.998043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.95 -0.0879589 31.1067 398.492 0.43508 102.66 +EDGE_SE3:QUAT 1270 1271 6.36892 -0.235919 -0.351455 -0.00466008 0.0654277 0.0110209 0.997786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.633 0.051163 33.2382 398.281 1.24656 103.039 +EDGE_SE3:QUAT 1271 1272 6.27609 0.0295116 -0.429726 0.00140802 0.065528 -0.017086 0.997703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.65 -0.123995 33.2685 398.284 -0.20651 103.022 +EDGE_SE3:QUAT 1272 1273 6.35224 -0.0636227 -0.390599 0.00458397 0.0651207 -0.0261363 0.997525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.588 -0.169209 33.1038 398.3 -1.03885 102.956 +EDGE_SE3:QUAT 1273 1274 6.15911 -0.164483 -0.555666 0.00147681 0.0646339 0.00589484 0.997891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.491 0.056259 32.7884 398.329 -0.510269 102.963 +EDGE_SE3:QUAT 1274 1275 6.28843 -0.127801 -0.507534 -0.00301283 0.0728304 -0.016107 0.99721 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.976 -0.183722 37.0604 397.88 1.10962 103.752 +EDGE_SE3:QUAT 1275 1276 6.2427 0.0626399 -0.3638 0.00174722 0.0518037 -0.0114187 0.99859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.516 -0.0458919 26.1562 398.926 -0.406449 101.885 +EDGE_SE3:QUAT 1276 1277 6.17248 -0.0642882 -0.306885 0.00969068 0.0620447 -0.0195959 0.997834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.058 -0.0695855 31.5512 398.43 -2.64758 102.733 +EDGE_SE3:QUAT 1277 1278 6.11498 -0.0413086 -0.456354 0.00629737 0.0629096 -0.0111885 0.997937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.2 -0.0355877 31.9352 398.404 -1.73655 102.813 +EDGE_SE3:QUAT 1278 1279 6.25378 -0.174784 -0.257661 0.000242322 0.0615854 -0.0552106 0.996574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.943 -0.380153 31.1242 398.506 0.576252 102.372 +EDGE_SE3:QUAT 1279 1280 6.17019 0.0616008 -0.393819 0.00232753 0.0678128 0.0102412 0.997643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.045 0.105089 34.4403 398.161 -0.820432 103.259 +EDGE_SE3:QUAT 1280 1281 6.18631 -0.0294208 -0.500332 0.00097078 0.0621578 -0.0165373 0.997929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.076 -0.110164 31.5058 398.456 -0.0932231 102.714 +EDGE_SE3:QUAT 1281 1282 6.16046 -0.152861 -0.463147 -0.00284966 0.059529 -0.0114926 0.998156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.64 -0.0936667 30.1127 398.582 0.977618 102.497 +EDGE_SE3:QUAT 1282 1283 6.48933 -0.114148 -0.558952 0.00792116 0.0661857 0.00229604 0.997773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.734 0.0797257 33.5928 398.23 -2.37808 103.129 +EDGE_SE3:QUAT 1283 1284 6.23021 0.0689084 -0.49952 0.00236106 0.0617484 -0.0294253 0.997655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.011 -0.18902 31.3089 398.478 -0.356123 102.621 +EDGE_SE3:QUAT 1284 1285 6.21662 -0.0675519 -0.509614 -0.00175122 0.0678966 0.025668 0.997361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.069 0.203653 34.5102 398.16 0.191721 103.214 +EDGE_SE3:QUAT 1285 1286 6.24696 -0.00355016 -0.421317 -0.00685297 0.0657275 0.0278295 0.997426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.699 0.169067 33.4625 398.259 1.68811 103.018 +EDGE_SE3:QUAT 1286 1287 6.27844 -0.125261 -0.484204 -0.000515717 0.0582242 0.00484119 0.998292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.449 0.0266154 29.4618 398.644 0.0995189 102.399 +EDGE_SE3:QUAT 1287 1288 6.30194 -0.175161 -0.519588 0.00268912 0.0649816 0.00222882 0.99788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.55 0.0375932 32.9726 398.309 -0.825307 103 +EDGE_SE3:QUAT 1288 1289 6.15168 0.185523 -0.541771 0.00585665 0.063529 -0.0119178 0.997892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.306 -0.0453037 32.2574 398.375 -1.5954 102.866 +EDGE_SE3:QUAT 1289 1290 6.06952 -0.136027 -0.407924 -0.00274634 0.0605133 -0.00366496 0.998157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.804 -0.0435186 30.6415 398.533 0.858373 102.596 +EDGE_SE3:QUAT 1290 1291 6.16751 -0.0684213 -0.49552 0.000122103 0.0591053 0.0166265 0.998113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.582 0.107017 29.9085 398.605 -0.223843 102.446 +EDGE_SE3:QUAT 1291 1292 6.38761 -0.0557133 -0.479586 -0.00203821 0.0583076 -0.0319355 0.997786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.433 -0.211099 29.4345 398.648 0.962469 102.298 +EDGE_SE3:QUAT 1292 1293 6.09212 -0.171625 -0.299539 0.00668666 0.0703359 -0.0208016 0.997284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.531 -0.133962 35.8587 398.008 -1.70692 103.502 +EDGE_SE3:QUAT 1293 1294 6.18646 -0.154189 -0.195278 -0.00545553 0.0581331 -0.031623 0.997793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.373 -0.229353 29.2764 398.651 1.97474 102.285 +EDGE_SE3:QUAT 1294 1295 6.24633 -0.0847706 -0.482392 0.00778063 0.065566 0.00760576 0.997789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.615 0.119269 33.2408 398.265 -2.40241 103.061 +EDGE_SE3:QUAT 1295 1296 6.26818 -0.146763 -0.431497 0.0024718 0.0621254 -0.00389065 0.998058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.071 -0.00987631 31.4924 398.454 -0.68831 102.739 +EDGE_SE3:QUAT 1296 1297 6.16198 -0.0799677 -0.242041 0.00248522 0.0560917 -0.0256333 0.998093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.129 -0.131855 28.3798 398.742 -0.463845 102.164 +EDGE_SE3:QUAT 1297 1298 6.09268 -0.137636 -0.358679 0.00345629 0.0636609 -0.00638285 0.997945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.328 -0.0220124 32.2996 398.375 -0.949161 102.878 +EDGE_SE3:QUAT 1298 1299 6.20567 -0.169428 -0.399089 -0.00390056 0.0600442 -0.0299531 0.997739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.69 -0.223039 30.3047 398.563 1.50264 102.457 +EDGE_SE3:QUAT 1299 1300 6.19215 -0.193602 -0.357342 0.0117872 0.0568637 -0.0018283 0.998311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.189 0.0646013 28.7663 398.665 -3.48674 102.331 +EDGE_SE3:QUAT 1300 1301 6.22112 -0.0285158 -0.401262 -0.00283696 0.0645106 -0.0027672 0.997909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.468 -0.0423644 32.7252 398.333 0.875704 102.956 +EDGE_SE3:QUAT 1301 1302 6.34695 -0.123071 -0.457444 0.00534104 0.0648657 -0.045263 0.996853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.549 -0.310754 33.0052 398.319 -1.02999 102.801 +EDGE_SE3:QUAT 1302 1303 6.29111 -0.166395 -0.306891 -0.0039401 0.0619004 0.0219111 0.997834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.041 0.126114 31.4098 398.464 0.912864 102.679 +EDGE_SE3:QUAT 1303 1304 6.31488 -0.202562 -0.344266 -0.00180194 0.0676507 0.00210826 0.997705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.025 0.00339086 34.3764 398.168 0.507397 103.255 +EDGE_SE3:QUAT 1304 1305 6.35699 -0.141824 -0.373519 0.00328607 0.0664864 -0.0108025 0.997723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.82 -0.0622093 33.7826 398.229 -0.839355 103.136 +EDGE_SE3:QUAT 1305 1306 6.30369 -0.190767 -0.443207 -0.000947004 0.0648154 -0.0419844 0.997013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.488 -0.329446 32.8093 398.336 0.796273 102.795 +EDGE_SE3:QUAT 1306 1307 6.44043 -0.123385 -0.501931 -0.0103694 0.0618439 -0.00573958 0.998015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.967 -0.113544 31.2984 398.44 3.14761 102.736 +EDGE_SE3:QUAT 1307 1308 6.21538 -0.152431 -0.359177 -0.000956901 0.0656536 -0.0291541 0.997416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.65 -0.237534 33.2833 398.284 0.645291 102.971 +EDGE_SE3:QUAT 1308 1309 6.27574 -0.154201 -0.518586 -0.000736652 0.0576042 0.00494137 0.998327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.354 0.0251876 29.1413 398.673 0.164682 102.347 +EDGE_SE3:QUAT 1309 1310 6.09744 -0.226017 -0.258046 -0.00450929 0.0574311 -0.02178 0.998102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.292 -0.159755 28.9748 398.68 1.581 102.285 +EDGE_SE3:QUAT 1310 1311 6.20693 -0.0159063 -0.19181 -0.00607085 0.0640601 0.0181051 0.997763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.402 0.0915393 32.5542 398.347 1.58266 102.899 +EDGE_SE3:QUAT 1311 1312 6.29708 -0.158061 -0.146104 0.00502495 0.0673067 0.0053706 0.997705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.946 0.0843908 34.1748 398.182 -1.55782 103.223 +EDGE_SE3:QUAT 1312 1313 6.34431 -0.0177462 -0.298745 0.000515654 0.060422 -0.0283971 0.997769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.787 -0.18609 30.587 398.545 0.173638 102.505 +EDGE_SE3:QUAT 1313 1314 6.24302 -0.30347 -0.375339 0.000292597 0.0597631 -0.0117893 0.998143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.688 -0.0750593 30.2571 398.572 0.0473083 102.517 +EDGE_SE3:QUAT 1314 1315 6.31953 -0.237597 -0.21995 -0.000950772 0.0626254 0.0233161 0.997764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.151 0.160742 31.745 398.435 0.00533797 102.728 +EDGE_SE3:QUAT 1315 1316 6.11825 -0.118747 -0.465761 0.0012453 0.0625985 0.0393635 0.997261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.115 0.290461 31.6555 398.446 -0.838167 102.614 +EDGE_SE3:QUAT 1316 1317 6.22251 -0.171544 -0.378444 -0.000708706 0.0691547 -0.0296095 0.997166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.279 -0.265844 35.1209 398.096 0.593991 103.309 +EDGE_SE3:QUAT 1317 1318 6.21844 -0.0718262 -0.339217 -0.000886513 0.0682154 -0.0010049 0.99767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.128 -0.0157371 34.67 398.138 0.275619 103.31 +EDGE_SE3:QUAT 1318 1319 6.2523 -0.194656 -0.254226 0.00226874 0.0614836 0.0336801 0.997537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.931 0.248058 31.0708 398.497 -1.06827 102.558 +EDGE_SE3:QUAT 1319 1320 6.34696 -0.123717 -0.29561 -0.0032256 0.0559529 -0.0104099 0.998374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.093 -0.0796217 28.2615 398.746 1.07167 102.205 +EDGE_SE3:QUAT 1320 1321 6.16656 0.0333055 -0.377473 0.00219706 0.0585098 -0.0333268 0.997728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.493 -0.19427 29.6238 398.635 -0.280683 102.316 +EDGE_SE3:QUAT 1321 1322 6.24314 -0.130521 -0.364895 0.00319419 0.0518749 -0.00372443 0.998642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.523 1.59982e-05 26.1904 398.92 -0.914409 101.904 +EDGE_SE3:QUAT 1322 1323 6.22752 -0.134193 -0.414806 -0.00742901 0.0605215 -0.0182576 0.997972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.753 -0.172783 30.5556 398.525 2.41841 102.568 +EDGE_SE3:QUAT 1323 1324 6.2488 0.0423297 -0.47685 -0.000323838 0.0570012 -0.0152156 0.998258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.258 -0.09236 28.8183 398.702 0.262423 102.276 +EDGE_SE3:QUAT 1324 1325 6.18545 -0.0947276 -0.346643 -0.00197504 0.0690576 -0.0103784 0.997557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.274 -0.10715 35.096 398.093 0.71951 103.381 +EDGE_SE3:QUAT 1325 1326 6.23699 -0.298 -0.228957 -9.35808e-05 0.0637253 0.000298159 0.997967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.339 0.00153094 32.3208 398.376 0.0241851 102.883 +EDGE_SE3:QUAT 1326 1327 6.23197 -0.26787 -0.390065 0.00498763 0.066327 -0.0191497 0.997602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.797 -0.116348 33.7291 398.233 -1.2401 103.103 +EDGE_SE3:QUAT 1327 1328 6.18426 -0.144952 -0.475915 -0.00460551 0.058755 0.00766808 0.998232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.529 0.0177789 29.756 398.612 1.28342 102.448 +EDGE_SE3:QUAT 1328 1329 6.18676 0.0648548 -0.499528 0.0034305 0.0677949 0.00114695 0.997693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.046 0.0370822 34.4469 398.158 -1.03153 103.272 +EDGE_SE3:QUAT 1329 1330 6.15092 -0.0838465 -0.440878 0.000600958 0.0625814 0.0251683 0.997722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.134 0.184711 31.6957 398.439 -0.47743 102.711 +EDGE_SE3:QUAT 1330 1331 6.23806 -0.221246 -0.303774 -0.000746063 0.06464 -0.00253098 0.997905 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.495 -0.025007 32.7969 398.329 0.252321 102.967 +EDGE_SE3:QUAT 1331 1332 6.27513 -0.0853939 -0.411111 0.0063143 0.0601579 -0.0202761 0.997963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.759 -0.0913881 30.5319 398.54 -1.64442 102.544 +EDGE_SE3:QUAT 1332 1333 6.2786 -0.223558 -0.195378 0.00476654 0.0635452 0.0140383 0.997869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.28 0.138603 32.1775 398.382 -1.58413 102.847 +EDGE_SE3:QUAT 1333 1334 6.39039 -0.00275384 -0.533357 -0.0111887 0.0678156 0.000851013 0.997635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.006 -0.0821924 34.4627 398.123 3.30569 103.308 +EDGE_SE3:QUAT 1334 1335 6.20043 -0.159617 -0.424376 -0.00743284 0.0557902 -0.0266295 0.99806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.01 -0.19602 28.0572 398.748 2.49782 102.131 +EDGE_SE3:QUAT 1335 1336 6.42572 -0.102746 -0.535746 0.00243001 0.0646274 -0.0108449 0.997848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.495 -0.0649314 32.8046 398.328 -0.588741 102.958 +EDGE_SE3:QUAT 1336 1337 6.28704 -0.147034 -0.470362 0.00168504 0.05843 -0.0270786 0.997923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.48 -0.157996 29.5757 398.638 -0.198751 102.346 +EDGE_SE3:QUAT 1337 1338 6.30014 -0.112928 -0.302107 -0.00216905 0.0714265 -0.0329903 0.996898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.685 -0.327441 36.2757 397.972 1.0823 103.513 +EDGE_SE3:QUAT 1338 1339 6.11531 -0.33832 -0.345553 -0.00515507 0.0585613 0.0203779 0.998062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.508 0.0939294 29.6894 398.621 1.30507 102.401 +EDGE_SE3:QUAT 1339 1340 6.02633 -0.164862 -0.27763 -0.00467247 0.0678489 0.0179629 0.997523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.068 0.114953 34.5207 398.153 1.15621 103.254 +EDGE_SE3:QUAT 1340 1341 6.2373 -0.126054 -0.476603 0.000459292 0.062038 -0.0333284 0.997517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.045 -0.23147 31.418 398.469 0.256531 102.615 +EDGE_SE3:QUAT 1341 1342 6.25852 -0.103477 -0.434705 -0.0103897 0.0577135 0.022113 0.998034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.369 0.0675146 29.3247 398.633 2.84623 102.356 +EDGE_SE3:QUAT 1342 1343 6.34528 -0.0859691 -0.300043 -0.00647937 0.0669017 0.0441456 0.996761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.913 0.31418 34.1 398.207 1.36542 103.013 +EDGE_SE3:QUAT 1343 1344 6.22885 -0.170272 -0.494296 -0.00558942 0.06314 0.0253845 0.997666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.251 0.145386 32.0852 398.397 1.35599 102.782 +EDGE_SE3:QUAT 1344 1345 6.15728 -0.0504386 -0.358963 -0.00546516 0.0698502 -0.0131304 0.997456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.395 -0.162918 35.4767 398.044 1.79054 103.457 +EDGE_SE3:QUAT 1345 1346 6.0505 -0.157932 -0.318045 -0.00662709 0.0621588 -0.0205473 0.997833 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.021 -0.191742 31.4039 398.449 2.21122 102.699 +EDGE_SE3:QUAT 1346 1347 6.47365 -0.000612863 -0.514904 0.00480506 0.0646335 0.000169435 0.997897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.484 0.0373665 32.7936 398.322 -1.42806 102.973 +EDGE_SE3:QUAT 1347 1348 6.2339 -0.00389345 -0.419243 0.00539131 0.0605658 -0.0259977 0.997811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.828 -0.137866 30.744 398.525 -1.30251 102.549 +EDGE_SE3:QUAT 1348 1349 6.14442 -0.166148 -0.547432 -7.96309e-06 0.060688 -0.0136252 0.998064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.835 -0.0919084 30.7338 398.528 0.159729 102.592 +EDGE_SE3:QUAT 1349 1350 6.24987 0.0348018 -0.347181 0.005654 0.0622979 0.00101004 0.998041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.086 0.0476709 31.5721 398.438 -1.6912 102.762 +EDGE_SE3:QUAT 1350 1351 6.35901 -0.154356 -0.41679 0.00738477 0.0551221 -0.00415794 0.998444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.967 0.0224241 27.8741 398.768 -2.15416 102.166 +EDGE_SE3:QUAT 1351 1352 6.34683 -0.147685 -0.477567 -0.00240054 0.0628218 -0.0456402 0.996978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.129 -0.345055 31.7169 398.439 1.25823 102.575 +EDGE_SE3:QUAT 1352 1353 6.17108 -0.117185 -0.379815 -0.00156157 0.0742956 -0.0248614 0.996925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.262 -0.266927 37.8288 397.8 0.804387 103.869 +EDGE_SE3:QUAT 1353 1354 6.19896 -0.153606 -0.36276 0.0028221 0.0677129 -0.0460009 0.99664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.031 -0.365564 34.4201 398.18 -0.250554 103.05 +EDGE_SE3:QUAT 1354 1355 6.21077 -0.109665 -0.333462 0.00131042 0.0689138 0.00856035 0.997585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.251 0.0854569 35.0277 398.101 -0.498863 103.371 +EDGE_SE3:QUAT 1355 1356 6.02145 0.0205289 -0.549595 -0.0016891 0.0599017 0.0104879 0.998148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.713 0.057383 30.3388 398.564 0.382372 102.534 +EDGE_SE3:QUAT 1356 1357 6.19608 -0.175023 -0.492295 -0.00430388 0.0693724 -0.00811171 0.997549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.323 -0.107143 35.2532 398.071 1.38048 103.42 +EDGE_SE3:QUAT 1357 1358 6.32081 -0.0949116 -0.47565 -0.0027949 0.0685678 0.000398759 0.997642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.19 -0.0192046 34.8561 398.117 0.823149 103.347 +EDGE_SE3:QUAT 1358 1359 6.16269 0.02142 -0.447676 0.00190188 0.0699285 -0.00301616 0.997546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.444 -0.011339 35.5743 398.043 -0.523898 103.482 +EDGE_SE3:QUAT 1359 1360 6.17655 -0.0299125 -0.316326 -0.00659131 0.0677085 0.0229517 0.997419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.048 0.141481 34.4828 398.154 1.66209 103.23 +EDGE_SE3:QUAT 1360 1361 6.30924 0.0763557 -0.559063 0.00303109 0.0665188 -0.0249351 0.997469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.828 -0.179361 33.809 398.231 -0.5866 103.088 +EDGE_SE3:QUAT 1361 1362 6.18382 -0.127721 -0.356647 -0.00276585 0.0651896 0.00331228 0.997864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.589 0.00485008 33.0908 398.298 0.77991 103.021 +EDGE_SE3:QUAT 1362 1363 6.35586 -0.36993 -0.284798 0.000656631 0.0581436 -0.0173898 0.998157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.435 -0.103168 29.4179 398.649 -0.00203364 102.364 +EDGE_SE3:QUAT 1363 1364 6.17803 -0.186773 -0.527587 0.00936824 0.0609397 -0.0225466 0.997843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.882 -0.0886525 30.9865 398.487 -2.52233 102.622 +EDGE_SE3:QUAT 1364 1365 6.31881 -0.229596 -0.495082 -0.000641826 0.0634327 -0.00716109 0.99796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.288 -0.0575312 32.1636 398.391 0.276574 102.85 +EDGE_SE3:QUAT 1365 1366 6.31475 -0.197426 -0.278192 0.00117809 0.053572 0.00283241 0.998559 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.759 0.0218318 27.0549 398.852 -0.380041 102.028 +EDGE_SE3:QUAT 1366 1367 6.16042 -0.221415 -0.379171 -0.0028669 0.0613447 -0.0198247 0.997916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.922 -0.156365 31.0328 398.497 1.08312 102.625 +EDGE_SE3:QUAT 1367 1368 6.05653 -0.171271 -0.254775 -0.0103919 0.058733 0.010728 0.998162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.506 -0.00146096 29.7887 398.586 2.96954 102.472 +EDGE_SE3:QUAT 1368 1369 6.08874 0.0328503 -0.387274 -0.00143209 0.0584727 -0.0294483 0.997854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.466 -0.19302 29.5388 398.639 0.755162 102.329 +EDGE_SE3:QUAT 1369 1370 6.11512 -0.0346746 -0.42042 0.0025056 0.0538511 -0.0146051 0.998439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.803 -0.0623396 27.2184 398.839 -0.594822 102.033 +EDGE_SE3:QUAT 1370 1371 6.2184 -0.393157 -0.348097 0.00309573 0.0623811 0.0356594 0.99741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.066 0.274875 31.5116 398.454 -1.34248 102.621 +EDGE_SE3:QUAT 1371 1372 6.05691 -0.26693 -0.55506 -0.00148151 0.0645712 0.010241 0.997859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.485 0.0672734 32.7687 398.332 0.314726 102.952 +EDGE_SE3:QUAT 1372 1373 6.10713 -0.124195 -0.254268 0.00562121 0.0691933 -0.0128044 0.997505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.31 -0.0668471 35.224 398.075 -1.49954 103.405 +EDGE_SE3:QUAT 1373 1374 6.23581 -0.26679 -0.548397 0.00383411 0.0604639 0.0177943 0.998004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.776 0.145108 30.5701 398.537 -1.34444 102.558 +EDGE_SE3:QUAT 1374 1375 6.26018 -0.154932 -0.306531 0.00413544 0.0705966 -0.0033882 0.997491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.566 0.00373106 35.9309 398.001 -1.17993 103.554 +EDGE_SE3:QUAT 1375 1376 6.04549 -0.32269 -0.421921 -0.00578472 0.0551858 -0.0285663 0.998051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.936 -0.192946 27.7637 398.781 2.0253 102.068 +EDGE_SE3:QUAT 1376 1377 5.9869 -0.226792 -0.364534 0.00470591 0.0632084 -0.0390796 0.997224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.263 -0.252928 32.1209 398.403 -0.929069 102.696 +EDGE_SE3:QUAT 1377 1378 6.24655 -0.0563683 -0.455999 -0.000192639 0.0678452 0.00724074 0.99767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.06 0.0597437 34.4755 398.159 -0.0351488 103.268 +EDGE_SE3:QUAT 1378 1379 6.14658 -0.296394 -0.269106 -0.00178305 0.0602725 -0.0161483 0.99805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.759 -0.11946 30.4975 398.549 0.715351 102.546 +EDGE_SE3:QUAT 1379 1380 6.17964 -0.369421 -0.379227 0.00390857 0.0651163 -0.0343884 0.997277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.585 -0.238658 33.0952 398.306 -0.736846 102.903 +EDGE_SE3:QUAT 1380 1381 6.24977 -0.0820678 -0.384023 -0.00297312 0.0552514 0.00369812 0.998461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.001 0.00225503 27.9297 398.776 0.845753 102.161 +EDGE_SE3:QUAT 1381 1382 6.13005 -0.183719 -0.368163 0.00981996 0.0629569 -0.0100198 0.997918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.191 -0.00153468 31.9767 398.384 -2.79625 102.838 +EDGE_SE3:QUAT 1382 1383 5.99288 -0.371239 -0.382527 0.00356507 0.0627112 -0.046402 0.996946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.171 -0.309447 31.8317 398.436 -0.506224 102.581 +EDGE_SE3:QUAT 1383 1384 6.35917 -0.13502 -0.395678 0.00800471 0.0575711 -0.00672952 0.998287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.333 0.0112152 29.1536 398.654 -2.30685 102.365 +EDGE_SE3:QUAT 1384 1385 6.20461 -0.00668903 -0.529339 0.000788925 0.0629471 -0.00170101 0.998015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.208 -0.00663118 31.9157 398.415 -0.213974 102.812 +EDGE_SE3:QUAT 1385 1386 6.10261 0.0345962 -0.451116 -0.000570172 0.0700173 0.0226552 0.997288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.455 0.199675 35.6085 398.044 -0.127865 103.437 +EDGE_SE3:QUAT 1386 1387 6.06628 -0.242093 -0.536489 0.008152 0.0599881 -0.0157552 0.998041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.723 -0.0482863 30.4479 398.539 -2.24293 102.554 +EDGE_SE3:QUAT 1387 1388 6.42854 -0.160517 -0.433313 0.00170318 0.0578885 -0.0255063 0.997996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.397 -0.145208 29.2963 398.662 -0.224197 102.309 +EDGE_SE3:QUAT 1388 1389 6.34016 -0.0943848 -0.271538 0.00125852 0.0671505 -0.00874535 0.997704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.937 -0.0625701 34.1165 398.196 -0.262733 103.199 +EDGE_SE3:QUAT 1389 1390 6.16941 -0.0900359 -0.255688 -0.00403328 0.0624514 -0.0377716 0.997325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.063 -0.296674 31.5166 398.451 1.64667 102.61 +EDGE_SE3:QUAT 1390 1391 6.04025 -0.24079 -0.238049 -0.00608545 0.0651492 -0.0211702 0.997632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.53 -0.210015 32.9669 398.299 2.06647 102.968 +EDGE_SE3:QUAT 1391 1392 6.3639 -0.199885 -0.159773 -0.000106252 0.0533356 0.0117026 0.998508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.726 0.060077 26.9328 398.863 -0.0885308 101.997 +EDGE_SE3:QUAT 1392 1393 6.25003 -0.279508 -0.367931 0.00330088 0.0669124 -0.0452615 0.996726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.892 -0.347028 34.0159 398.22 -0.408251 102.982 +EDGE_SE3:QUAT 1393 1394 6.21748 -0.160159 -0.290193 -0.00501322 0.0656006 -0.00468261 0.997822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.645 -0.0752963 33.2839 398.272 1.54522 103.061 +EDGE_SE3:QUAT 1394 1395 6.082 -0.222128 -0.478707 0.0046344 0.0616332 -0.00658935 0.998066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.988 -0.0131185 31.2482 398.474 -1.29959 102.698 +EDGE_SE3:QUAT 1395 1396 6.07123 0.103348 -0.331839 -0.00806105 0.0653357 0.0194853 0.997641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.621 0.0917724 33.2481 398.272 2.15147 103.025 +EDGE_SE3:QUAT 1396 1397 6.28588 -0.0463461 -0.361253 -0.00448591 0.069681 0.0129341 0.997475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.402 0.0785966 35.4718 398.052 1.16024 103.45 +EDGE_SE3:QUAT 1397 1398 6.20156 -0.118891 -0.409095 0.00870568 0.0699125 -0.0319225 0.997004 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.464 -0.216402 35.7042 398.024 -2.16131 103.419 +EDGE_SE3:QUAT 1398 1399 6.09568 -0.0658503 -0.291645 0.00953764 0.0589141 -0.0218296 0.997979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.558 -0.0754047 29.9339 398.583 -2.59036 102.451 +EDGE_SE3:QUAT 1399 1400 6.18937 -0.180996 -0.413041 0.00464447 0.0582437 -0.0190508 0.99811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.457 -0.0878207 29.5161 398.637 -1.16926 102.378 +EDGE_SE3:QUAT 1400 1401 5.99165 -0.154059 -0.204484 0.00243004 0.0641072 0.0185277 0.997768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.386 0.157411 32.4806 398.359 -0.946111 102.88 +EDGE_SE3:QUAT 1401 1402 6.05785 -0.0653862 -0.342765 0.00175219 0.0492021 -0.00500424 0.998775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.168 -0.012634 24.8157 399.031 -0.474745 101.708 +EDGE_SE3:QUAT 1402 1403 6.22215 -0.0829228 -0.464193 0.00469958 0.0692163 -0.0013918 0.99759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.304 0.0262983 35.1998 398.077 -1.37434 103.416 +EDGE_SE3:QUAT 1403 1404 6.21331 -0.153434 -0.400361 -0.00371096 0.0615603 0.00522184 0.998083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.977 0.0100725 31.2039 398.48 1.04138 102.69 +EDGE_SE3:QUAT 1404 1405 6.19031 -0.0573191 -0.335526 0.00491936 0.0636136 -0.00612613 0.997944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.317 -0.00929179 32.2798 398.374 -1.38666 102.878 +EDGE_SE3:QUAT 1405 1406 6.18312 -0.0382142 -0.540216 0.00439689 0.0569865 -0.0160579 0.998236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.264 -0.0672508 28.857 398.695 -1.13293 102.283 +EDGE_SE3:QUAT 1406 1407 6.1622 -0.126882 -0.267793 0.00736027 0.0645345 -0.023237 0.997618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.488 -0.123044 32.8337 398.318 -1.90103 102.931 +EDGE_SE3:QUAT 1407 1408 6.23149 -0.207789 -0.468071 -0.0055172 0.0619487 0.0145022 0.997959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.045 0.0628887 31.4386 398.455 1.46828 102.715 +EDGE_SE3:QUAT 1408 1409 6.11789 -0.103072 -0.356617 -0.00194281 0.0705347 -0.00518462 0.997494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.553 -0.0638365 35.8826 398.009 0.643642 103.54 +EDGE_SE3:QUAT 1409 1410 6.15333 -0.0880778 -0.330333 -0.000375822 0.0626322 -0.0373266 0.997338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.132 -0.270351 31.7 398.442 0.555715 102.636 +EDGE_SE3:QUAT 1410 1411 6.08747 -0.230189 -0.459166 0.000554601 0.0543762 -0.0220359 0.998277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.873 -0.115501 27.467 398.82 0.0652954 102.041 +EDGE_SE3:QUAT 1411 1412 6.27994 -0.0944692 -0.251418 0.00640089 0.0647636 -0.0291567 0.997454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.532 -0.177135 32.954 398.312 -1.54284 102.917 +EDGE_SE3:QUAT 1412 1413 6.2563 0.111186 -0.399352 0.00363682 0.0624264 0.00829358 0.998008 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.108 0.0852531 31.622 398.439 -1.17836 102.759 +EDGE_SE3:QUAT 1413 1414 6.26289 -0.139937 -0.51785 -0.000722536 0.0612848 -0.0342577 0.997532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.912 -0.240054 30.9993 398.507 0.614363 102.539 +EDGE_SE3:QUAT 1414 1415 6.1037 -0.174219 -0.370236 0.00752722 0.0621292 -0.0252566 0.99772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.084 -0.125619 31.5888 398.439 -1.93796 102.703 +EDGE_SE3:QUAT 1415 1416 6.19373 0.0312867 -0.412646 0.0030076 0.0694891 -0.0147845 0.997469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.366 -0.106713 35.3607 398.067 -0.698711 103.42 +EDGE_SE3:QUAT 1416 1417 5.97719 -0.153279 -0.233219 -0.0114774 0.0621944 -0.0281099 0.997602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.943 -0.277677 31.2906 398.429 3.74212 102.675 +EDGE_SE3:QUAT 1417 1418 6.17937 -0.126027 -0.400826 0.00608053 0.0581986 -0.00215816 0.998284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.432 0.0266498 29.4547 398.634 -1.7843 102.41 +EDGE_SE3:QUAT 1418 1419 6.25898 -0.0528018 -0.512342 0.00372313 0.0579396 -0.0737355 0.995586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.391 -0.428767 29.3356 398.684 -0.287178 101.835 +EDGE_SE3:QUAT 1419 1420 6.24686 -0.0848768 -0.398167 -0.00518972 0.0605703 -0.00620581 0.998131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.799 -0.077467 30.6558 398.526 1.61381 102.602 +EDGE_SE3:QUAT 1420 1421 6.23642 -0.183417 -0.306788 0.00161272 0.0640797 -0.0147699 0.997834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.401 -0.0993351 32.5141 398.358 -0.299686 102.895 +EDGE_SE3:QUAT 1421 1422 6.18093 -0.156664 -0.43569 0.00999802 0.0580467 -0.00025233 0.998264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.381 0.0640057 29.3677 398.622 -2.97058 102.416 +EDGE_SE3:QUAT 1422 1423 6.09856 -0.200275 -0.510928 0.00631682 0.0614579 -0.00904848 0.998049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.957 -0.0181596 31.1722 398.476 -1.77096 102.686 +EDGE_SE3:QUAT 1423 1424 6.23155 -0.180851 -0.404976 -0.00613971 0.0675302 -0.0364646 0.997032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.91 -0.351106 34.1227 398.184 2.28466 103.094 +EDGE_SE3:QUAT 1424 1425 5.95385 -0.118479 -0.515534 0.00585336 0.0647252 -0.0171492 0.997739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.515 -0.0880883 32.8966 398.314 -1.52738 102.963 +EDGE_SE3:QUAT 1425 1426 6.05494 -0.247218 -0.467427 0.00179279 0.0664788 -0.000702858 0.997786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.815 0.00824908 33.7607 398.231 -0.522907 103.142 +EDGE_SE3:QUAT 1426 1427 5.96243 -0.0742347 -0.202936 -0.0020489 0.0649609 -0.0214801 0.997654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.531 -0.181451 32.9232 398.316 0.871713 102.946 +EDGE_SE3:QUAT 1427 1428 6.18918 -0.156636 -0.291154 -0.00022855 0.0579338 -0.0403221 0.997506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.382 -0.24816 29.2597 398.669 0.515377 102.207 +EDGE_SE3:QUAT 1428 1429 6.08753 -0.0190211 -0.445059 0.0138709 0.061805 -0.0292431 0.997563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.021 -0.107664 31.5464 398.411 -3.77701 102.708 +EDGE_SE3:QUAT 1429 1430 6.21752 -0.139977 -0.277539 -0.00149204 0.0737159 0.00267303 0.997275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.172 0.0134945 37.5721 397.826 0.404734 103.876 +EDGE_SE3:QUAT 1430 1431 6.13333 -0.118259 -0.462708 0.0112741 0.0617758 0.00346141 0.99802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.952 0.103933 31.2761 398.437 -3.38953 102.74 +EDGE_SE3:QUAT 1431 1432 5.99663 -0.257932 -0.197358 -0.00175614 0.0645598 -0.0562857 0.996324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.408 -0.439859 32.5945 398.362 1.21107 102.619 +EDGE_SE3:QUAT 1432 1433 6.08133 -0.245919 -0.464953 0.0100258 0.0606183 -0.0305016 0.997645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.841 -0.137106 30.8667 398.499 -2.62756 102.561 +EDGE_SE3:QUAT 1433 1434 6.34284 -0.111503 -0.364125 -0.00454317 0.057402 0.00650466 0.99832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.32 0.00979515 29.052 398.675 1.28001 102.337 +EDGE_SE3:QUAT 1434 1435 6.15365 -0.187555 -0.408228 0.00802124 0.0570157 -0.0322141 0.997821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.28 -0.141043 28.9678 398.681 -2.03479 102.231 +EDGE_SE3:QUAT 1435 1436 6.08677 -0.305591 -0.329864 -0.00861588 0.0644033 -0.00563088 0.997871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.412 -0.10704 32.6404 398.321 2.62569 102.96 +EDGE_SE3:QUAT 1436 1437 6.17393 -0.182168 -0.220124 -0.00446242 0.0587663 0.0225843 0.998006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.54 0.113267 29.7905 398.614 1.07354 102.407 +EDGE_SE3:QUAT 1437 1438 6.2243 -0.278793 -0.226109 0.00303002 0.0655703 0.017374 0.997692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.635 0.159968 33.2411 398.282 -1.11398 103.021 +EDGE_SE3:QUAT 1438 1439 6.19107 -0.06378 -0.45245 -0.00378921 0.0635574 0.0194748 0.997781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.317 0.116661 32.2681 398.381 0.890626 102.838 +EDGE_SE3:QUAT 1439 1440 5.91366 -0.116944 -0.321484 0.00170162 0.0595644 -0.0649518 0.996108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.626 -0.408962 30.1053 398.608 0.234746 102.083 +EDGE_SE3:QUAT 1440 1441 6.18863 0.128748 -0.552268 0.00896623 0.0538643 -0.00578897 0.998491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.779 0.0230822 27.2375 398.815 -2.60985 102.075 +EDGE_SE3:QUAT 1441 1442 6.12783 -0.221019 -0.244211 0.00302781 0.0567987 0.0115419 0.998314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.219 0.0872271 28.6971 398.709 -1.02644 102.27 +EDGE_SE3:QUAT 1442 1443 6.12316 -0.171644 -0.254996 0.000682707 0.0650235 -0.0199725 0.997684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.558 -0.149813 32.9948 398.312 0.0426999 102.962 +EDGE_SE3:QUAT 1443 1444 6.20766 -0.160746 -0.462858 0.00310179 0.0590416 0.000856525 0.99825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.571 0.0262323 29.8826 398.603 -0.93187 102.472 +EDGE_SE3:QUAT 1444 1445 6.09538 -0.214699 -0.294306 -0.00403089 0.0563639 -0.0362356 0.997744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.114 -0.233932 28.3708 398.736 1.59192 102.106 +EDGE_SE3:QUAT 1445 1446 6.01016 -0.153446 -0.203129 0.0103709 0.0620067 -0.0112269 0.997959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.033 -0.00527099 31.4921 398.428 -2.94819 102.755 +EDGE_SE3:QUAT 1446 1447 6.19772 -0.13341 -0.367262 0.00322406 0.0657188 -0.00998251 0.997783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.685 -0.0544968 33.3793 398.269 -0.832752 103.064 +EDGE_SE3:QUAT 1447 1448 6.075 -0.202533 -0.273878 0.00229997 0.0614609 0.0173225 0.997957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.947 0.135795 31.1068 398.491 -0.885741 102.646 +EDGE_SE3:QUAT 1448 1449 6.0769 -0.157555 -0.271993 -0.00160618 0.0595302 0.00641547 0.998205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.653 0.0307426 30.1433 398.582 0.404669 102.508 +EDGE_SE3:QUAT 1449 1450 6.04936 -0.152104 -0.334901 -0.00758561 0.0623125 0.0160231 0.997899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.103 0.0598959 31.6521 398.429 2.06351 102.754 +EDGE_SE3:QUAT 1450 1451 6.0736 -0.0261451 -0.419548 0.00986466 0.0516819 -0.0275633 0.998234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.503 -0.078757 26.2331 398.901 -2.66435 101.855 +EDGE_SE3:QUAT 1451 1452 6.12136 -0.140748 -0.39245 0.00741422 0.0672917 0.0155659 0.997584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.905 0.187392 34.1023 398.178 -2.39545 103.2 +EDGE_SE3:QUAT 1452 1453 6.07048 -0.0358362 -0.298025 -0.0022375 0.073589 0.0324041 0.99676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 407.144 0.304103 37.5114 397.842 0.218926 103.758 +EDGE_SE3:QUAT 1453 1454 6.03095 -0.341544 -0.236688 0.00746276 0.0623184 -0.0378283 0.997311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.125 -0.217384 31.7221 398.434 -1.76918 102.644 +EDGE_SE3:QUAT 1454 1455 5.96737 -0.118697 -0.317615 0.00274966 0.0528494 -0.0123743 0.998522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.661 -0.0469834 26.7023 398.881 -0.693039 101.963 +EDGE_SE3:QUAT 1455 1456 6.15516 -0.219293 -0.339482 -0.00288601 0.056941 -0.0527398 0.996979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.185 -0.327493 28.6254 398.723 1.43617 101.997 +EDGE_SE3:QUAT 1456 1457 6.28059 -0.178807 -0.39012 0.00444621 0.0580371 -0.0185158 0.998133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.425 -0.0850868 29.4058 398.647 -1.11699 102.361 +EDGE_SE3:QUAT 1457 1458 6.05287 -0.118721 -0.385972 0.00561932 0.06901 -0.0197034 0.997406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.282 -0.127104 35.145 398.086 -1.41029 103.367 +EDGE_SE3:QUAT 1458 1459 5.89172 -0.0725097 -0.296829 0.00100631 0.0676606 -0.0317986 0.997201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.018 -0.259471 34.3666 398.177 0.10625 103.152 +EDGE_SE3:QUAT 1459 1460 6.13755 -0.206726 -0.437175 -0.00275878 0.064817 0.0152306 0.997777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.529 0.0967566 32.9101 398.318 0.632219 102.965 +EDGE_SE3:QUAT 1460 1461 6.05655 0.01612 -0.407569 0.00259921 0.0629483 -0.000500662 0.998013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.206 0.0152281 31.9162 398.413 -0.765842 102.814 +EDGE_SE3:QUAT 1461 1462 6.11832 -0.121048 -0.487158 0.00132801 0.0584975 0.0110476 0.998226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.486 0.0778687 29.5898 398.632 -0.518359 102.41 +EDGE_SE3:QUAT 1462 1463 5.99079 -0.20462 -0.386277 -0.000832722 0.059903 0.00631716 0.998184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.712 0.0358128 30.3337 398.565 0.175421 102.54 +EDGE_SE3:QUAT 1463 1464 6.06114 -0.159668 -0.488708 -0.00173654 0.0565452 -0.0463625 0.997321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.15 -0.279963 28.4835 398.736 1.02051 102.035 +EDGE_SE3:QUAT 1464 1465 6.05344 -0.152504 -0.467002 -0.00697345 0.0561209 -0.0285615 0.997991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.06 -0.206276 28.2244 398.736 2.38332 102.144 +EDGE_SE3:QUAT 1465 1466 5.79639 -0.250515 -0.353694 -0.00090307 0.0529522 0.0146121 0.99849 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.674 0.0694272 26.7409 398.879 0.119925 101.961 +EDGE_SE3:QUAT 1466 1467 6.05326 -0.360524 -0.38023 -0.00235675 0.0604424 -0.0437134 0.997211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.747 -0.306488 30.491 398.554 1.20491 102.384 +EDGE_SE3:QUAT 1467 1468 6.13361 -0.172173 -0.400285 0.00244723 0.0703556 -0.00957766 0.997473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.526 -0.0668342 35.8076 398.018 -0.598856 103.519 +EDGE_SE3:QUAT 1468 1469 5.87955 -0.0870466 -0.320997 0.0084158 0.0674298 -0.0490285 0.996483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.02 -0.346309 34.4417 398.171 -1.87351 103.035 +EDGE_SE3:QUAT 1469 1470 6.1625 -0.0770182 -0.261371 0.0061667 0.0560979 -0.00701989 0.998382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.12 -0.00156859 28.3855 398.729 -1.75959 102.236 +EDGE_SE3:QUAT 1470 1471 6.01587 -0.198168 -0.677768 -0.00462365 0.0515476 0.0212529 0.998434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.485 0.0769025 26.0651 398.931 1.16626 101.843 +EDGE_SE3:QUAT 1471 1472 5.98135 0.0381998 -0.319193 0.00328388 0.0651937 0.0109176 0.997808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.576 0.109954 33.0606 398.299 -1.10878 103.007 +EDGE_SE3:QUAT 1472 1473 6.03524 -0.228531 -0.444687 -0.00170354 0.0613264 -0.0329972 0.997571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.912 -0.238357 31.0034 398.505 0.891411 102.549 +EDGE_SE3:QUAT 1473 1474 6.15876 -0.147951 -0.482231 -0.00168033 0.0591021 -0.0510105 0.996946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.532 -0.334713 29.7883 398.623 1.07693 102.198 +EDGE_SE3:QUAT 1474 1475 6.07276 -0.319651 -0.215809 -0.00607152 0.0497716 -0.000561251 0.998742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.227 -0.0356156 25.1001 398.998 1.81535 101.76 +EDGE_SE3:QUAT 1475 1476 6.19029 -0.0943584 -0.251671 0.0058191 0.0538502 -0.0101638 0.99848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.797 -0.0189823 27.2341 398.829 -1.6275 102.054 +EDGE_SE3:QUAT 1476 1477 6.02899 -0.315797 -0.546651 0.0091822 0.0590729 -0.0301556 0.997756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.595 -0.132108 30.0475 398.579 -2.39018 102.423 +EDGE_SE3:QUAT 1477 1478 5.99699 -0.308442 -0.256416 0.000714638 0.0597268 -0.0256482 0.997885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.679 -0.162511 30.2328 398.577 0.0796973 102.461 +EDGE_SE3:QUAT 1478 1479 6.02757 0.0471519 -0.422199 0.00408765 0.0703875 -0.0198353 0.997314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.537 -0.146978 35.8508 398.015 -0.94971 103.498 +EDGE_SE3:QUAT 1479 1480 6.16629 -0.150351 -0.45152 0.00409286 0.0604283 -0.0129735 0.99808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.798 -0.0586076 30.6326 398.534 -1.06713 102.58 +EDGE_SE3:QUAT 1480 1481 5.90642 -0.176904 -0.332377 0.00138928 0.0615671 0.00867385 0.998064 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.975 0.0699943 31.1864 398.484 -0.514197 102.68 +EDGE_SE3:QUAT 1481 1482 5.98013 -0.288847 -0.35072 0.00854021 0.0631106 0.0245237 0.997669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.147 0.239255 31.8466 398.396 -2.82986 102.768 +EDGE_SE3:QUAT 1482 1483 5.89233 -0.1167 -0.176689 -0.000195461 0.0551798 -0.0342514 0.997889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.977 -0.191169 27.8516 398.79 0.421527 102.032 +EDGE_SE3:QUAT 1483 1484 6.07312 -0.130923 -0.344971 0.00278827 0.0654222 -0.0431003 0.996923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.627 -0.317747 33.2247 398.299 -0.294549 102.857 +EDGE_SE3:QUAT 1484 1485 6.16322 -0.190019 -0.280612 0.00357409 0.055647 -0.0450672 0.997426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.065 -0.233257 28.1748 398.767 -0.582065 101.995 +EDGE_SE3:QUAT 1485 1486 6.09943 -0.193193 -0.323324 0.00424419 0.0602937 -0.024253 0.997877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.782 -0.132583 30.582 398.542 -0.982948 102.528 +EDGE_SE3:QUAT 1486 1487 6.00874 0.0768275 -0.41798 0.00891223 0.0607542 -0.0107916 0.998055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.835 -0.0111202 30.8289 398.498 -2.5235 102.635 +EDGE_SE3:QUAT 1487 1488 5.63109 -0.160346 -0.225785 -0.000956942 0.0553697 -0.024592 0.998163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.008 -0.143297 27.9539 398.778 0.546397 102.105 +EDGE_SE3:QUAT 1488 1489 6.05897 0.057926 -0.316827 -0.00584507 0.0603419 -0.000506772 0.998161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.767 -0.0435925 30.5565 398.533 1.74293 102.591 +EDGE_SE3:QUAT 1489 1490 6.16847 -0.309778 -0.2984 -0.00441829 0.0659864 -0.0214151 0.997581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.691 -0.204517 33.4265 398.259 1.5773 103.043 +EDGE_SE3:QUAT 1490 1491 6.09984 -0.120332 -0.37713 0.00540905 0.0578657 0.0045215 0.998299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.376 0.0629507 29.2584 398.653 -1.65882 102.376 +EDGE_SE3:QUAT 1491 1492 5.88367 -0.0629221 -0.209305 -0.00713072 0.0635832 -0.0104352 0.997897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.275 -0.129424 32.1944 398.371 2.24266 102.867 +EDGE_SE3:QUAT 1492 1493 6.068 -0.230995 -0.281951 -0.00741954 0.0584575 -0.00610501 0.998244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.452 -0.087073 29.5506 398.618 2.27454 102.429 +EDGE_SE3:QUAT 1493 1494 5.91328 -0.354315 -0.32983 0.00896635 0.0517059 -0.0619741 0.996697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.537 -0.255128 26.3475 398.916 -2.05276 101.552 +EDGE_SE3:QUAT 1494 1495 6.00362 -0.242939 -0.477028 0.00406493 0.0589501 -0.0197329 0.998058 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.567 -0.0984922 29.8763 398.606 -0.98664 102.432 +EDGE_SE3:QUAT 1495 1496 6.05784 -0.119466 -0.520138 0.0017121 0.0614057 -0.0513807 0.996788 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.936 -0.342415 31.0902 398.509 0.0924039 102.405 +EDGE_SE3:QUAT 1496 1497 5.97743 -0.266069 -0.398548 0.00243487 0.0536177 -0.0351622 0.997939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.769 -0.17014 27.1029 398.854 -0.362026 101.912 +EDGE_SE3:QUAT 1497 1498 6.03483 -0.00999005 -0.424085 0.000240509 0.0562896 -0.0224263 0.998163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.151 -0.128196 28.4497 398.736 0.170489 102.19 +EDGE_SE3:QUAT 1498 1499 5.94019 -0.291595 -0.392269 -0.00411806 0.0536261 -0.0117488 0.998483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.75 -0.0859648 27.0509 398.847 1.34766 102.021 +EDGE_SE3:QUAT 1499 1500 5.94704 -0.17863 -0.26738 9.75573e-05 0.0549059 -0.00947664 0.998447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.951 -0.0515429 27.7434 398.795 0.0708989 102.123 +EDGE_SE3:QUAT 1500 1501 5.98286 -0.170064 -0.198508 0.00414564 0.0626857 -0.0664067 0.995813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.157 -0.449447 31.8199 398.451 -0.439237 102.352 +EDGE_SE3:QUAT 1501 1502 5.99281 -0.117677 -0.118552 0.00169054 0.0564385 0.00584785 0.998388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.174 0.044718 28.5295 398.725 -0.566275 102.251 +EDGE_SE3:QUAT 1502 1503 6.16767 -0.179064 -0.349133 -0.00321004 0.0705323 -0.0303889 0.997041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.51 -0.304072 35.7937 398.02 1.35176 103.439 +EDGE_SE3:QUAT 1503 1504 5.95318 -0.172401 -0.427493 -0.00125745 0.0664207 -0.0214358 0.997561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.791 -0.183213 33.6975 398.24 0.641257 103.085 +EDGE_SE3:QUAT 1504 1505 5.8782 -0.172979 -0.431631 -0.00613593 0.0573431 -0.0161136 0.998206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.274 -0.135897 28.9343 398.678 2.00229 102.305 +EDGE_SE3:QUAT 1505 1506 5.84763 -0.151272 -0.536484 0.0117215 0.0637782 -0.0294349 0.997461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.36 -0.13449 32.5371 398.33 -3.12432 102.865 +EDGE_SE3:QUAT 1506 1507 5.87092 -0.222001 -0.456434 -0.00257548 0.0605651 -0.0115187 0.998094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.806 -0.0950374 30.6525 398.533 0.898191 102.586 +EDGE_SE3:QUAT 1507 1508 6.0398 -0.270812 -0.166162 0.00213311 0.0539892 0.000389115 0.998539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.818 0.0148758 27.2716 398.833 -0.639211 102.062 +EDGE_SE3:QUAT 1508 1509 5.91221 -0.289195 -0.412727 -0.00158867 0.0602927 -0.050122 0.99692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.721 -0.342035 30.4109 398.566 1.04964 102.309 +EDGE_SE3:QUAT 1509 1510 5.85272 -0.37319 -0.561597 -0.00178861 0.0677552 -0.0145515 0.997594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.033 -0.136938 34.4053 398.166 0.715488 103.241 +EDGE_SE3:QUAT 1510 1511 5.78371 -0.198786 -0.348603 0.00857962 0.0463676 -0.00366505 0.998881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.787 0.0287698 23.3769 399.118 -2.5267 101.538 +EDGE_SE3:QUAT 1511 1512 5.92286 -0.194858 -0.0916729 0.00322614 0.0610265 -0.044008 0.99716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.893 -0.278156 30.9481 398.518 -0.447238 102.452 +EDGE_SE3:QUAT 1512 1513 6.01927 -0.042442 -0.385958 0.00011634 0.0615392 0.00281616 0.998101 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.975 0.0203567 31.1814 398.485 -0.0674882 102.685 +EDGE_SE3:QUAT 1513 1514 5.95877 -0.194465 -0.326077 0.00241146 0.0532705 -0.00812837 0.998544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.719 -0.0278401 26.9124 398.863 -0.634837 102.002 +EDGE_SE3:QUAT 1514 1515 6.0762 -0.265267 -0.492219 -0.000219665 0.0560326 -0.0053584 0.998415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.117 -0.0321022 28.3254 398.744 0.122936 102.219 +EDGE_SE3:QUAT 1515 1516 5.98213 -0.0818445 -0.240155 0.00474699 0.0598829 -0.0195471 0.998003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.715 -0.096191 30.3682 398.559 -1.18799 102.515 +EDGE_SE3:QUAT 1516 1517 5.87105 -0.134005 -0.440708 0.00586886 0.0526875 0.00753641 0.998565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.613 0.0722218 26.5718 398.881 -1.82473 101.963 +EDGE_SE3:QUAT 1517 1518 5.92085 -0.313127 -0.314374 -0.00379535 0.0595385 -0.00123711 0.998218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.647 -0.0337019 30.1389 398.578 1.14229 102.516 +EDGE_SE3:QUAT 1518 1519 6.00421 -0.112948 -0.446379 -0.00107609 0.0666631 -0.000503546 0.997775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.848 -0.0125183 33.8562 398.222 0.325442 103.159 +EDGE_SE3:QUAT 1519 1520 5.95863 -0.122336 -0.385533 0.00356323 0.0612124 -0.0182363 0.997952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.927 -0.100361 31.0429 398.498 -0.846482 102.631 +EDGE_SE3:QUAT 1520 1521 5.82393 -0.191902 -0.301191 0.0039769 0.0552961 -0.0366152 0.99779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.017 -0.180453 28.0022 398.777 -0.794917 102.039 +EDGE_SE3:QUAT 1521 1522 5.7463 -0.29481 -0.337992 -0.00177696 0.0586045 -0.0162826 0.998147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.497 -0.113892 29.6322 398.628 0.710696 102.404 +EDGE_SE3:QUAT 1522 1523 6.06437 -0.251527 -0.25787 -0.00213524 0.0599174 -0.0339105 0.997625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.681 -0.236295 30.2601 398.573 1.02254 102.42 +EDGE_SE3:QUAT 1523 1524 6.01187 -0.134671 -0.284085 -0.000954408 0.0543214 -0.0356853 0.997885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.847 -0.197236 27.3895 398.828 0.657446 101.953 +EDGE_SE3:QUAT 1524 1525 5.892 -0.179557 -0.515688 -0.000140433 0.0607962 -0.0109392 0.99809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.853 -0.0749925 30.791 398.522 0.168264 102.608 +EDGE_SE3:QUAT 1525 1526 5.8185 -0.133914 -0.141418 -5.43804e-05 0.0566313 -0.021689 0.99816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.201 -0.12732 28.623 398.72 0.251578 102.221 +EDGE_SE3:QUAT 1526 1527 5.83975 -0.199714 -0.382486 -4.05643e-05 0.0533709 -0.0382114 0.997843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.717 -0.198269 26.9159 398.869 0.405326 101.862 +EDGE_SE3:QUAT 1527 1528 5.91736 -0.241596 -0.420749 0.000289448 0.0614451 -0.032533 0.99758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.947 -0.22264 31.1076 398.498 0.294307 102.567 +EDGE_SE3:QUAT 1528 1529 5.79337 -0.134957 -0.550117 0.00154442 0.058781 -0.0214189 0.99804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.535 -0.125132 29.7573 398.62 -0.218835 102.403 +EDGE_SE3:QUAT 1529 1530 5.88823 -0.103277 -0.346065 -0.000853591 0.0498742 -0.00475273 0.998744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.255 -0.026184 25.1527 399.005 0.300317 101.754 +EDGE_SE3:QUAT 1530 1531 5.91472 -0.187818 -0.375774 0.00204608 0.0666388 -0.000452464 0.997775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.843 0.0122855 33.8443 398.222 -0.601113 103.158 +EDGE_SE3:QUAT 1531 1532 5.88493 -0.211666 -0.523099 -0.000526529 0.0517949 -0.0148612 0.998547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.51 -0.075615 26.1322 398.928 0.305439 101.872 +EDGE_SE3:QUAT 1532 1533 5.82982 -0.380093 -0.476638 0.00194025 0.057044 -0.0062952 0.99835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.269 -0.0249875 28.8563 398.697 -0.50849 102.301 +EDGE_SE3:QUAT 1533 1534 5.92871 -0.209305 -0.399149 -0.00258456 0.0486181 -0.0230637 0.998548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.075 -0.112514 24.4622 399.056 0.988253 101.612 +EDGE_SE3:QUAT 1534 1535 5.95962 -0.300768 -0.382427 0.000884085 0.0494085 -0.0596946 0.996993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.173 -0.259594 24.8669 399.04 0.309439 101.36 +EDGE_SE3:QUAT 1535 1536 5.83785 -0.119313 -0.301585 0.00334621 0.0594028 -0.0452021 0.997205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.635 -0.269848 30.109 398.596 -0.4821 102.302 +EDGE_SE3:QUAT 1536 1537 5.95114 -0.25736 -0.281579 -0.00113009 0.0618208 -0.0385114 0.997343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.99 -0.27657 31.2567 398.484 0.788768 102.552 +EDGE_SE3:QUAT 1537 1538 5.87094 -0.3729 -0.208277 -0.0103884 0.0686279 -0.0132155 0.997501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.12 -0.19783 34.7895 398.09 3.24885 103.352 +EDGE_SE3:QUAT 1538 1539 5.84388 -0.150725 -0.349349 0.00694296 0.0588038 -0.050066 0.996989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.563 -0.272758 29.9088 398.612 -1.5021 102.228 +EDGE_SE3:QUAT 1539 1540 5.81634 -0.135421 -0.555087 -0.000441263 0.0568859 -0.00932038 0.998337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.243 -0.0579142 28.7631 398.706 0.23281 102.281 +EDGE_SE3:QUAT 1540 1541 5.63269 -0.238251 -0.330804 0.00802293 0.0534531 0.0105811 0.998482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.7 0.102355 26.9385 398.841 -2.49827 102.022 +EDGE_SE3:QUAT 1541 1542 5.72755 -0.120957 -0.372014 0.00501838 0.0569226 -0.0207264 0.998151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.257 -0.0908774 28.8401 398.697 -1.26716 102.264 +EDGE_SE3:QUAT 1542 1543 5.99108 0.0197304 -0.265671 0.00211644 0.0643023 -0.0387413 0.997176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.432 -0.27822 32.6274 398.355 -0.156647 102.786 +EDGE_SE3:QUAT 1543 1544 6.19967 -0.0738819 -0.254256 -0.00180574 0.0447336 -0.0169427 0.998854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.607 -0.0701539 22.4994 399.2 0.686664 101.38 +EDGE_SE3:QUAT 1544 1545 5.80372 -0.190032 -0.208933 0.00820591 0.0554196 -0.04198 0.997546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.05 -0.186523 28.1783 398.754 -1.99596 102.034 +EDGE_SE3:QUAT 1545 1546 5.90347 -0.220884 -0.140256 -0.00207456 0.0662108 -0.0440338 0.996831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.713 -0.368349 33.4989 398.265 1.1663 102.904 +EDGE_SE3:QUAT 1546 1547 5.67361 -0.293754 -0.41847 -0.00394186 0.0566212 -0.00164091 0.998387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.197 -0.0346747 28.6266 398.713 1.19065 102.273 +EDGE_SE3:QUAT 1547 1548 5.81023 -0.230911 -0.205293 -0.00353991 0.0608884 0.000507807 0.998138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.865 -0.0211894 30.8442 398.513 1.04598 102.632 +EDGE_SE3:QUAT 1548 1549 5.91899 -0.330966 -0.474763 0.00819755 0.0569632 -0.0123291 0.998266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.248 -0.0206475 28.8657 398.681 -2.30432 102.308 +EDGE_SE3:QUAT 1549 1550 5.84152 -0.0485259 -0.3017 -0.00757539 0.0612946 0.0280523 0.997697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.949 0.140751 31.1644 398.481 1.9239 102.615 +EDGE_SE3:QUAT 1550 1551 6.0009 -0.22941 -0.520813 0.00681783 0.0603995 -0.0505275 0.996871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.815 -0.292872 30.732 398.537 -1.4448 102.359 +EDGE_SE3:QUAT 1551 1552 5.80783 -0.32215 -0.434128 0.0010323 0.0584695 -0.0178606 0.998129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.486 -0.104847 29.5907 398.634 -0.107495 102.39 +EDGE_SE3:QUAT 1552 1553 5.6913 -0.441063 -0.306862 -0.00108479 0.0569202 -0.0510336 0.997073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.207 -0.307084 28.6805 398.722 0.880838 102.019 +EDGE_SE3:QUAT 1553 1554 5.78404 -0.338284 -0.317967 -0.00594804 0.0585674 -0.0197571 0.99807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.457 -0.162548 29.5527 398.623 1.99003 102.391 +EDGE_SE3:QUAT 1554 1555 5.8828 -0.302725 -0.486025 0.0015906 0.0528026 -0.0464458 0.997523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.644 -0.226709 26.6533 398.895 -0.000393642 101.753 +EDGE_SE3:QUAT 1555 1556 5.8463 -0.146008 -0.253573 0.00592719 0.0565096 -0.044278 0.997402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.206 -0.222213 28.6848 398.719 -1.28401 102.085 +EDGE_SE3:QUAT 1556 1557 5.88169 -0.0990942 -0.408735 0.00241195 0.0611144 -0.016825 0.997986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.909 -0.0983196 30.9782 398.505 -0.521136 102.624 +EDGE_SE3:QUAT 1557 1558 5.82589 -0.166206 -0.358672 -0.00244494 0.0549663 -0.0171693 0.998338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.947 -0.109451 27.7421 398.793 0.909183 102.105 +EDGE_SE3:QUAT 1558 1559 5.95843 -0.127235 -0.44534 -0.000272136 0.0584805 -0.0365487 0.997619 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.469 -0.229792 29.5501 398.642 0.489785 102.282 +EDGE_SE3:QUAT 1559 1560 5.6615 -0.215944 -0.416092 8.33052e-05 0.0570262 -0.0188287 0.998195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.262 -0.111294 28.832 398.702 0.180834 102.265 +EDGE_SE3:QUAT 1560 1561 5.76049 -0.29065 -0.573953 0.00303608 0.0537446 -0.036862 0.997869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.789 -0.17651 27.1814 398.847 -0.522667 101.912 +EDGE_SE3:QUAT 1561 1562 5.81755 -0.0890094 -0.54307 0.00230936 0.0558564 0.0090326 0.998395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.084 0.0658485 28.2204 398.751 -0.784066 102.199 +EDGE_SE3:QUAT 1562 1563 5.69892 -0.190968 -0.264943 0.00922301 0.0575867 -0.0290692 0.997875 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.363 -0.117329 29.274 398.647 -2.42328 102.305 +EDGE_SE3:QUAT 1563 1564 6.12145 -0.215822 -0.489462 -0.00199588 0.0515452 -0.00930729 0.998625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.474 -0.056347 26.0003 398.937 0.687331 101.868 +EDGE_SE3:QUAT 1564 1565 5.92713 -0.250536 -0.332552 0.00699596 0.0586358 -0.0263344 0.997908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.524 -0.119815 29.7696 398.61 -1.78551 102.391 +EDGE_SE3:QUAT 1565 1566 5.83814 -0.173257 -0.327372 -0.00574726 0.0540429 -0.0472356 0.997404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.736 -0.282074 27.0723 398.841 2.20469 101.825 +EDGE_SE3:QUAT 1566 1567 5.66148 -0.192818 -0.217624 -0.00259134 0.0566773 -0.0177982 0.998231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.197 -0.120678 28.6224 398.716 0.964371 102.239 +EDGE_SE3:QUAT 1567 1568 5.82959 -0.212556 -0.381363 0.00137648 0.0612835 -0.0146179 0.998012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.934 -0.090929 31.0552 398.498 -0.238672 102.643 +EDGE_SE3:QUAT 1568 1569 5.81956 -0.211381 -0.352314 -0.000524475 0.0515921 -0.056004 0.997097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.45 -0.272881 25.9437 398.953 0.716046 101.555 +EDGE_SE3:QUAT 1569 1570 5.83564 -0.356768 -0.558223 -0.00531501 0.0631124 -0.0206867 0.997778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.192 -0.188915 31.9173 398.405 1.82591 102.781 +EDGE_SE3:QUAT 1570 1571 5.83171 -0.181027 -0.400486 0.00458736 0.0532845 -0.0369612 0.997885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.731 -0.165052 26.9802 398.862 -0.98691 101.883 +EDGE_SE3:QUAT 1571 1572 5.85581 -0.165517 -0.537131 -0.0100794 0.0562352 -0.0364985 0.997699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.014 -0.269865 28.1623 398.722 3.39474 102.104 +EDGE_SE3:QUAT 1572 1573 5.90662 -0.094729 -0.291514 0.00295437 0.0609245 -0.0322243 0.997618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.879 -0.198793 30.8919 398.518 -0.504266 102.533 +EDGE_SE3:QUAT 1573 1574 5.90962 -0.35592 -0.277949 0.0038555 0.0564713 -0.0462411 0.997325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.189 -0.245762 28.6079 398.73 -0.646306 102.052 +EDGE_SE3:QUAT 1574 1575 5.69246 -0.441492 -0.428471 -0.00119893 0.0646322 -0.0202007 0.997704 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.481 -0.163615 32.766 398.333 0.60266 102.922 +EDGE_SE3:QUAT 1575 1576 5.71801 -0.351783 -0.346667 0.00481904 0.0576154 0.000947627 0.998327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.345 0.0370562 29.142 398.665 -1.44385 102.357 +EDGE_SE3:QUAT 1576 1577 5.77244 -0.230265 -0.342915 -0.000383107 0.0575028 -0.0216847 0.99811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.331 -0.133392 29.0691 398.681 0.352614 102.292 +EDGE_SE3:QUAT 1577 1578 5.96243 -0.147179 -0.37116 -0.000326861 0.0662405 -0.0246731 0.997499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.762 -0.201149 33.6105 398.251 0.405059 103.053 +EDGE_SE3:QUAT 1578 1579 5.68104 -0.261293 -0.391156 -0.00268655 0.0563437 -0.00999309 0.998358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.154 -0.0748443 28.468 398.729 0.907358 102.236 +EDGE_SE3:QUAT 1579 1580 5.68544 -0.0248533 -0.444981 -0.000117127 0.0529986 -0.0324829 0.998066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.668 -0.166753 26.7331 398.883 0.366878 101.876 +EDGE_SE3:QUAT 1580 1581 5.93609 -0.169332 -0.181955 0.00780232 0.0604708 -0.014869 0.998029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.8 -0.0458808 30.6917 398.518 -2.14755 102.596 +EDGE_SE3:QUAT 1581 1582 5.54992 -0.152544 -0.285497 0.00247254 0.060412 -0.0100316 0.99812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.795 -0.0500209 30.6084 398.538 -0.619455 102.58 +EDGE_SE3:QUAT 1582 1583 5.67688 -0.139629 -0.367766 -0.00112331 0.0565546 -0.0361766 0.997743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.171 -0.217703 28.536 398.73 0.726903 102.125 +EDGE_SE3:QUAT 1583 1584 5.8078 -0.332436 -0.396811 0.00152037 0.0499697 -0.0192044 0.998565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.27 -0.0790448 25.2142 399.002 -0.267549 101.727 +EDGE_SE3:QUAT 1584 1585 5.77208 -0.121083 -0.305198 -0.00154713 0.0549998 -0.0454586 0.99745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.927 -0.2589 27.6956 398.804 0.9421 101.921 +EDGE_SE3:QUAT 1585 1586 5.70439 -0.0246809 -0.428153 -0.00203913 0.06284 -0.0363917 0.997358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.152 -0.276883 31.7718 398.432 1.03998 102.658 +EDGE_SE3:QUAT 1586 1587 5.94212 -0.104465 -0.20606 -0.00438712 0.0618468 -0.0267598 0.997717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.981 -0.217499 31.2456 398.473 1.61807 102.634 +EDGE_SE3:QUAT 1587 1588 5.83269 -0.284165 -0.494471 0.00691578 0.0514049 -0.052036 0.997297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.483 -0.213677 26.0995 398.936 -1.54403 101.624 +EDGE_SE3:QUAT 1588 1589 5.70446 -0.2841 -0.283626 0.00446278 0.0596946 -0.0299026 0.997759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.688 -0.165254 30.2816 398.572 -0.986326 102.448 +EDGE_SE3:QUAT 1589 1590 5.68211 -0.25275 -0.158042 0.00238755 0.0610551 -0.0225575 0.997877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.899 -0.137471 30.9491 398.51 -0.447472 102.596 +EDGE_SE3:QUAT 1590 1591 5.3438 -0.36873 -0.190521 0.00292762 0.0579683 -0.0425666 0.997406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.41 -0.242751 29.3565 398.663 -0.398534 102.202 +EDGE_SE3:QUAT 1591 1592 5.78099 -0.294512 -0.425263 -0.000167753 0.0559909 -0.0392858 0.997658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.092 -0.22535 28.2602 398.756 0.472454 102.057 +EDGE_SE3:QUAT 1592 1593 5.57376 -0.201251 -0.444932 -0.00278995 0.0620868 -0.00708083 0.998042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.057 -0.0698593 31.4525 398.457 0.912159 102.73 +EDGE_SE3:QUAT 1593 1594 5.71974 -0.20467 -0.283885 0.00169392 0.0704354 -0.0371785 0.996822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 406.529 -0.325404 35.8307 398.027 -0.0118227 103.392 +EDGE_SE3:QUAT 1594 1595 5.75849 -0.20117 -0.357509 -0.0144913 0.0565553 -0.0101864 0.998242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.077 -0.150625 28.4959 398.662 4.42209 102.305 +EDGE_SE3:QUAT 1595 1596 5.61286 -0.0884936 -0.31422 -0.00215563 0.0634635 -0.0651082 0.995856 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.197 -0.490835 31.9652 398.426 1.4273 102.403 +EDGE_SE3:QUAT 1596 1597 5.77492 -0.109292 -0.125878 -0.00699724 0.0494704 -0.0317816 0.998245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.134 -0.177414 24.7857 399.016 2.39142 101.624 +EDGE_SE3:QUAT 1597 1598 5.66117 -0.061563 -0.391314 0.00590113 0.0588845 -0.0378794 0.997528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.567 -0.202041 29.9028 398.607 -1.3288 102.334 +EDGE_SE3:QUAT 1598 1599 5.70526 -0.276877 -0.441099 -0.00467773 0.0590745 -0.0414872 0.99738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.507 -0.293231 29.73 398.615 1.86011 102.285 +EDGE_SE3:QUAT 1599 1600 5.60682 -0.120076 -0.330928 0.00420833 0.0616661 -0.017553 0.997934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.001 -0.0927184 31.285 398.474 -1.04457 102.676 +EDGE_SE3:QUAT 1600 1601 5.64771 -0.279165 -0.443105 -0.00164877 0.056486 -0.0128394 0.998319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.177 -0.0852 28.5435 398.725 0.629595 102.24 +EDGE_SE3:QUAT 1601 1602 5.81012 -0.109233 -0.309062 0.00574934 0.0492999 -0.0683493 0.996426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.197 -0.274039 24.9963 399.033 -1.06016 101.268 +EDGE_SE3:QUAT 1602 1603 5.70761 -0.264572 -0.515114 0.0014951 0.0557363 -0.0367207 0.997769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.068 -0.198964 28.1726 398.764 -0.0519416 102.062 +EDGE_SE3:QUAT 1603 1604 5.56281 -0.154022 -0.286283 0.00153113 0.0620934 -0.0215173 0.997837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.066 -0.141157 31.4773 398.46 -0.201117 102.69 +EDGE_SE3:QUAT 1604 1605 5.61783 -0.0363336 -0.268403 0.00255485 0.0550984 -0.0263073 0.998131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.983 -0.130267 27.8683 398.786 -0.482118 102.082 +EDGE_SE3:QUAT 1605 1606 5.74654 -0.18503 -0.349848 0.00380228 0.0550481 -0.0347754 0.997871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.98 -0.16954 27.8694 398.788 -0.764099 102.031 +EDGE_SE3:QUAT 1606 1607 5.76855 -0.165762 -0.152218 0.0115143 0.0573212 -0.0397128 0.997499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.334 -0.166556 29.2344 398.646 -2.98977 102.234 +EDGE_SE3:QUAT 1607 1608 5.63459 -0.338279 -0.284295 0.0110611 0.0546935 -0.0306885 0.99797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.929 -0.101294 27.8207 398.765 -2.97049 102.078 +EDGE_SE3:QUAT 1608 1609 5.73145 -0.0978749 -0.280522 -0.00418319 0.0623039 -0.0245141 0.997747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.061 -0.203415 31.4963 398.45 1.5327 102.688 +EDGE_SE3:QUAT 1609 1610 5.67285 -0.333748 -0.336244 0.00506384 0.0515705 -0.0581914 0.99696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.495 -0.254979 26.1278 398.941 -0.928654 101.556 +EDGE_SE3:QUAT 1610 1611 5.53061 -0.231102 -0.283425 -0.000993547 0.0514551 0.0252301 0.998356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.465 0.116091 25.9679 398.944 0.0453203 101.806 +EDGE_SE3:QUAT 1611 1612 5.5764 0.00283082 -0.230684 0.00267263 0.0571339 -0.0380185 0.997639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.283 -0.209914 28.9208 398.699 -0.37897 102.17 +EDGE_SE3:QUAT 1612 1613 5.64868 -0.286334 -0.280741 0.00756897 0.0653663 -0.0307359 0.997359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.639 -0.184607 33.2947 398.276 -1.86663 102.972 +EDGE_SE3:QUAT 1613 1614 5.74863 -0.217187 -0.232726 0.00191376 0.057123 -0.0398828 0.997568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.276 -0.225578 28.8954 398.702 -0.132738 102.151 +EDGE_SE3:QUAT 1614 1615 5.68037 -0.233575 -0.373229 0.00291667 0.0563863 -0.00979621 0.998357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.171 -0.0384721 28.5249 398.726 -0.762044 102.245 +EDGE_SE3:QUAT 1615 1616 5.78489 -0.209503 -0.292304 0.00180057 0.0582074 -0.0117594 0.998234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.448 -0.0610357 29.4616 398.644 -0.404704 102.388 +EDGE_SE3:QUAT 1616 1617 5.60224 -0.178294 -0.329285 -0.0015753 0.0620946 -0.0290344 0.997647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.043 -0.215726 31.4166 398.465 0.81058 102.644 +EDGE_SE3:QUAT 1617 1618 5.4853 -0.336129 -0.462814 -0.00570503 0.0546029 -0.0184396 0.998322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.87 -0.134409 27.5132 398.802 1.89221 102.076 +EDGE_SE3:QUAT 1618 1619 5.65201 -0.208786 -0.318516 -0.000604161 0.0567488 0.00227237 0.998386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.224 0.00951705 28.6979 398.712 0.15506 102.279 +EDGE_SE3:QUAT 1619 1620 5.71771 -0.319449 -0.41066 0.00332085 0.0556176 -0.0415892 0.99758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.06 -0.21479 28.1532 398.767 -0.544171 102.022 +EDGE_SE3:QUAT 1620 1621 5.54848 -0.282517 -0.358541 0.0110607 0.0485661 -0.0527874 0.997363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.117 -0.171647 24.7811 399.022 -2.80155 101.449 +EDGE_SE3:QUAT 1621 1622 5.53183 0.00483989 -0.35496 -0.00250825 0.0571062 -0.0420613 0.997479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.232 -0.264926 28.7675 398.708 1.20729 102.119 +EDGE_SE3:QUAT 1622 1623 5.53053 -0.383895 -0.163466 0.00136117 0.0594235 -0.0607735 0.99638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.605 -0.382295 30.0299 398.612 0.286529 102.123 +EDGE_SE3:QUAT 1623 1624 5.67842 -0.409818 -0.337252 -0.00137842 0.0590054 -0.036433 0.997592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.541 -0.240282 29.7966 398.618 0.820839 102.325 +EDGE_SE3:QUAT 1624 1625 5.75103 -0.248264 -0.4541 0.00642706 0.0489172 -0.00217427 0.99878 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.117 0.0248689 24.6724 399.03 -1.89574 101.701 +EDGE_SE3:QUAT 1625 1626 5.66925 -0.191549 -0.565643 0.00610308 0.0548848 -0.0672008 0.99621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.967 -0.335061 27.8726 398.802 -1.10679 101.701 +EDGE_SE3:QUAT 1626 1627 5.41653 -0.29655 -0.217024 -0.00493575 0.0608665 -0.0432996 0.997194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.782 -0.324534 30.6414 398.531 1.97002 102.421 +EDGE_SE3:QUAT 1627 1628 5.49879 -0.207547 -0.490245 0.00054132 0.0571823 -0.0619626 0.996439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.25 -0.364924 28.838 398.717 0.519916 101.918 +EDGE_SE3:QUAT 1628 1629 5.36114 -0.0963816 -0.370428 0.00614716 0.0566555 -0.0710177 0.995846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.226 -0.380546 28.7862 398.728 -1.05619 101.79 +EDGE_SE3:QUAT 1629 1630 5.69037 -0.251802 -0.157803 0.00185479 0.0572738 -0.0387809 0.997603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.299 -0.22058 28.9729 398.695 -0.126242 102.172 +EDGE_SE3:QUAT 1630 1631 5.49614 -0.285244 -0.193573 -0.00728364 0.0518405 -0.0276398 0.998246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.452 -0.17531 26.0204 398.918 2.44733 101.822 +EDGE_SE3:QUAT 1631 1632 5.61857 -0.180084 -0.260074 0.00262514 0.0560788 -0.019331 0.998236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.128 -0.0946561 28.3725 398.741 -0.573367 102.192 +EDGE_SE3:QUAT 1632 1633 5.61879 -0.227054 -0.202296 0.000140205 0.0444882 -0.0166098 0.998872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.586 -0.0590264 22.3948 399.209 0.102143 101.367 +EDGE_SE3:QUAT 1633 1634 5.44046 -0.08572 -0.407531 0.00445079 0.0538834 -0.0462977 0.997463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.815 -0.219624 27.2915 398.841 -0.844995 101.85 +EDGE_SE3:QUAT 1634 1635 5.54424 -0.153366 -0.262257 0.00218649 0.064842 -0.00366688 0.997886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.53 -0.0118186 32.9084 398.317 -0.603937 102.987 +EDGE_SE3:QUAT 1635 1636 5.6326 -0.388838 -0.346591 -0.00538888 0.060036 -0.00259099 0.998178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.718 -0.0539103 30.3907 398.55 1.63134 102.561 +EDGE_SE3:QUAT 1636 1637 5.4785 -0.312539 -0.203813 0.00346157 0.051444 -0.0191353 0.998487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.47 -0.0728193 25.9942 398.938 -0.841442 101.839 +EDGE_SE3:QUAT 1637 1638 5.66111 -0.239979 -0.290939 0.00332466 0.06099 -0.060352 0.996307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.877 -0.388391 30.9163 398.531 -0.285878 102.275 +EDGE_SE3:QUAT 1638 1639 5.41803 -0.0392968 -0.216189 -0.00295227 0.0571013 -0.0174505 0.998212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.259 -0.122643 28.8386 398.696 1.06917 102.275 +EDGE_SE3:QUAT 1639 1640 5.62971 -0.214313 -0.276993 0.00463222 0.0511584 -0.0318833 0.998171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.436 -0.126532 25.8823 398.949 -1.06535 101.759 +EDGE_SE3:QUAT 1640 1641 5.75768 -0.199339 -0.281215 0.00577746 0.054423 -0.020049 0.9983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.887 -0.0736315 27.5573 398.805 -1.51043 102.071 +EDGE_SE3:QUAT 1641 1642 5.43598 -0.212853 -0.23949 0.00372516 0.0539101 -0.0348861 0.997929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.816 -0.163174 27.2814 398.838 -0.747332 101.942 +EDGE_SE3:QUAT 1642 1643 5.42725 -0.261564 -0.571297 -0.000483577 0.0555938 -0.059299 0.996691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.007 -0.335326 27.9895 398.786 0.779141 101.82 +EDGE_SE3:QUAT 1643 1644 5.42862 -0.13988 -0.44302 0.00066826 0.0567112 -0.0309747 0.99791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.211 -0.177607 28.6648 398.719 0.137917 102.178 +EDGE_SE3:QUAT 1644 1645 5.64125 -0.18543 -0.207965 -0.000731086 0.0510887 -0.0432608 0.997756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.394 -0.208897 25.7147 398.966 0.645744 101.648 +EDGE_SE3:QUAT 1645 1646 5.53901 -0.299434 -0.38595 0.00527064 0.0542014 0.010161 0.998464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.827 0.086058 27.3448 398.818 -1.67528 102.071 +EDGE_SE3:QUAT 1646 1647 5.46448 -0.124707 -0.180061 -0.00382973 0.0586938 -0.0459279 0.997212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.451 -0.31168 29.5338 398.637 1.65547 102.212 +EDGE_SE3:QUAT 1647 1648 5.63194 -0.0755708 -0.368714 0.00327415 0.0534702 -0.0293968 0.998131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.752 -0.134204 27.0429 398.856 -0.672443 101.941 +EDGE_SE3:QUAT 1648 1649 5.52432 -0.24094 -0.26555 0.00574839 0.0583419 -0.0245612 0.997978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.476 -0.115429 29.5932 398.629 -1.43578 102.368 +EDGE_SE3:QUAT 1649 1650 5.54032 -0.285128 -0.341258 -0.00458008 0.061741 -0.0356506 0.997445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.944 -0.279183 31.145 398.483 1.77986 102.564 +EDGE_SE3:QUAT 1650 1651 5.52155 -0.207308 -0.122315 -0.000385899 0.0620988 -0.0460053 0.997009 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.033 -0.326494 31.3986 398.475 0.658325 102.512 +EDGE_SE3:QUAT 1651 1652 5.27444 -0.236102 -0.404528 -0.00289525 0.0568242 -0.0189616 0.9982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.216 -0.130011 28.6917 398.71 1.06791 102.247 +EDGE_SE3:QUAT 1652 1653 5.51253 -0.220782 -0.167644 -0.00612719 0.047972 -0.0355759 0.998196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.947 -0.178776 24.016 399.079 2.15955 101.492 +EDGE_SE3:QUAT 1653 1654 5.38209 -0.314531 -0.468195 0.00707821 0.0540383 -0.0416337 0.997645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.847 -0.180892 27.4364 398.821 -1.67489 101.92 +EDGE_SE3:QUAT 1654 1655 5.53469 -0.158532 -0.279071 0.00747541 0.0558155 -0.0373191 0.997715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.104 -0.167013 28.3515 398.739 -1.82526 102.096 +EDGE_SE3:QUAT 1655 1656 5.47425 -0.182735 -0.315019 -0.00444697 0.0547537 -0.0405086 0.997668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.867 -0.246353 27.5106 398.809 1.75144 101.944 +EDGE_SE3:QUAT 1656 1657 5.55803 -0.23683 -0.218304 -0.00495348 0.066299 0.00553718 0.997772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.781 0.00629297 33.6817 398.234 1.40003 103.13 +EDGE_SE3:QUAT 1657 1658 5.54262 -0.238804 -0.360897 0.00668068 0.0513369 -0.0353556 0.998033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.466 -0.133065 26.023 398.934 -1.64032 101.761 +EDGE_SE3:QUAT 1658 1659 5.56632 -0.158518 -0.286174 -0.00415137 0.059327 -0.0310792 0.997746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.573 -0.226653 29.9232 398.597 1.58661 102.388 +EDGE_SE3:QUAT 1659 1660 5.42069 -0.481186 -0.478567 0.00564952 0.058132 -0.0172929 0.998143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.439 -0.0699517 29.4655 398.638 -1.4881 102.379 +EDGE_SE3:QUAT 1660 1661 5.72129 -0.0861371 -0.0544607 -0.00475739 0.052717 -0.00623562 0.998579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.625 -0.0592759 26.5968 398.883 1.48046 101.965 +EDGE_SE3:QUAT 1661 1662 5.52541 -0.248406 -0.425005 -0.00810499 0.0458262 -0.0388111 0.998162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.655 -0.185017 22.8545 399.153 2.76605 101.328 +EDGE_SE3:QUAT 1662 1663 5.60399 -0.138925 -0.218597 -0.00476924 0.0525249 -0.0141163 0.998508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.59 -0.0983973 26.4705 398.892 1.56374 101.931 +EDGE_SE3:QUAT 1663 1664 5.63845 -0.206175 -0.164425 -0.00152126 0.0510836 -0.0506172 0.99741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.377 -0.247335 25.6672 398.971 0.954517 101.574 +EDGE_SE3:QUAT 1664 1665 5.48893 -0.172662 -0.354478 -0.00632666 0.048483 -0.0049451 0.998792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.054 -0.0545097 24.4214 399.049 1.93312 101.666 +EDGE_SE3:QUAT 1665 1666 5.60033 -0.117329 -0.276369 0.00153472 0.0458735 -0.0253055 0.998626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.752 -0.0892537 23.117 399.16 -0.232106 101.421 +EDGE_SE3:QUAT 1666 1667 5.31158 -0.302827 -0.257372 -0.000125406 0.0567592 -0.0389106 0.997629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.207 -0.229213 28.6586 398.721 0.46102 102.122 +EDGE_SE3:QUAT 1667 1668 5.30232 -0.248693 -0.609168 0.0053123 0.0537797 -0.0615224 0.996642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.803 -0.294916 27.2716 398.85 -0.944106 101.683 +EDGE_SE3:QUAT 1668 1669 5.41677 -0.211496 -0.2647 0.00100202 0.0595994 -0.0192773 0.998036 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.663 -0.11852 30.1755 398.581 -0.0788026 102.48 +EDGE_SE3:QUAT 1669 1670 5.46626 -0.0506232 -0.434064 0.00363741 0.050192 -0.0229953 0.998468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.303 -0.0857108 25.3582 398.989 -0.861019 101.733 +EDGE_SE3:QUAT 1670 1671 5.52434 -0.137252 -0.341014 -0.00467611 0.0488311 -0.0110309 0.998735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.101 -0.0726105 24.5854 399.041 1.49875 101.674 +EDGE_SE3:QUAT 1671 1672 5.38058 -0.302676 -0.0714206 -0.00586298 0.0566538 -0.00935531 0.998333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.183 -0.0919652 28.6103 398.708 1.84603 102.269 +EDGE_SE3:QUAT 1672 1673 5.45055 -0.173234 -0.296356 0.000146213 0.0482473 -0.00913796 0.998794 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.045 -0.0379314 24.3204 399.069 0.0418829 101.634 +EDGE_SE3:QUAT 1673 1674 5.47176 -0.421152 -0.336756 0.00417308 0.0589847 -0.0111322 0.998188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.568 -0.0429979 29.8804 398.603 -1.11547 102.46 +EDGE_SE3:QUAT 1674 1675 5.48972 -0.260733 -0.242777 -0.00610239 0.0563102 -0.0308422 0.997918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.093 -0.215259 28.3257 398.731 2.14965 102.143 +EDGE_SE3:QUAT 1675 1676 5.18825 -0.287163 -0.161593 0.00311769 0.0606276 -0.00610311 0.998137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.827 -0.0195039 30.7185 398.527 -0.856072 102.606 +EDGE_SE3:QUAT 1676 1677 5.24264 -0.381415 -0.28704 -0.00423608 0.0580685 -0.0290503 0.997881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.381 -0.205638 29.2788 398.655 1.5829 102.296 +EDGE_SE3:QUAT 1677 1678 5.36808 -0.522253 -0.296253 -0.00427877 0.0612399 -0.0273814 0.997738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.882 -0.216884 30.9294 398.503 1.59064 102.577 +EDGE_SE3:QUAT 1678 1679 5.29391 -0.375306 -0.426814 -0.00594449 0.0561547 -0.0150244 0.998291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.1 -0.123483 28.3269 398.732 1.93087 102.212 +EDGE_SE3:QUAT 1679 1680 5.30603 -0.149564 -0.225105 0.0064112 0.0593394 -0.0622891 0.996272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.643 -0.361054 30.1798 398.597 -1.19983 102.132 +EDGE_SE3:QUAT 1680 1681 5.43539 -0.216739 -0.279844 -0.00321688 0.0571817 -0.0309954 0.997877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.253 -0.204805 28.8319 398.698 1.29686 102.211 +EDGE_SE3:QUAT 1681 1682 5.39725 -0.296233 -0.22819 -0.00634532 0.0568577 -0.0445804 0.997366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.141 -0.299597 28.5209 398.715 2.37555 102.073 +EDGE_SE3:QUAT 1682 1683 5.50438 -0.0940604 -0.384976 -0.00164545 0.0513032 -0.0325268 0.998152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.425 -0.164621 25.8307 398.953 0.813053 101.747 +EDGE_SE3:QUAT 1683 1684 5.39524 -0.221685 -0.14542 -0.00442265 0.0651962 -0.0167227 0.997723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.561 -0.16357 33.0323 398.299 1.51825 102.989 +EDGE_SE3:QUAT 1684 1685 5.47863 -0.290319 -0.26666 -0.00387509 0.0584354 -0.00631283 0.998264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.469 -0.0649776 29.5533 398.631 1.22283 102.417 +EDGE_SE3:QUAT 1685 1686 5.40783 -0.263143 -0.175894 0.00425891 0.0541166 -0.0403645 0.997709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.848 -0.190847 27.4034 398.829 -0.847806 101.919 +EDGE_SE3:QUAT 1686 1687 5.43558 -0.392199 -0.311421 -0.00206269 0.0549003 -0.0385954 0.997744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.917 -0.223708 27.6535 398.804 1.02197 101.973 +EDGE_SE3:QUAT 1687 1688 5.30549 -0.266912 -0.536441 0.00100157 0.0560609 -0.0267196 0.998069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.118 -0.147056 28.3393 398.747 -0.0107047 102.152 +EDGE_SE3:QUAT 1688 1689 5.40989 -0.0817816 -0.146584 0.000269803 0.051882 -0.0387925 0.997899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.513 -0.188383 26.157 398.931 0.308521 101.747 +EDGE_SE3:QUAT 1689 1690 5.43296 -0.096869 -0.280769 -0.00116662 0.0545128 -0.00190839 0.998511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.894 -0.0174339 27.5408 398.811 0.367324 102.101 +EDGE_SE3:QUAT 1690 1691 5.28814 -0.373082 -0.575759 0.00329306 0.0566388 -0.0894192 0.994377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.17 -0.502189 28.6094 398.759 -0.00280417 101.463 +EDGE_SE3:QUAT 1691 1692 5.33409 -0.22076 -0.218809 -0.00241783 0.056948 -0.032099 0.997858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.223 -0.20474 28.7233 398.71 1.06994 102.185 +EDGE_SE3:QUAT 1692 1693 5.3397 -0.135899 -0.339108 0.00509708 0.0523682 -0.0506795 0.997328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.606 -0.225323 26.5345 398.904 -1.00622 101.697 +EDGE_SE3:QUAT 1693 1694 5.39282 -0.0952923 -0.251287 0.00488852 0.0553175 -0.0354942 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.023 -0.168867 28.0327 398.773 -1.07811 102.053 +EDGE_SE3:QUAT 1694 1695 5.22027 -0.247357 -0.328483 -0.00352787 0.0584953 0.0205996 0.998069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.496 0.105756 29.635 398.629 0.818959 102.388 +EDGE_SE3:QUAT 1695 1696 5.26518 -0.167352 -0.412785 0.00733801 0.0544029 -0.0462387 0.997421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.902 -0.207337 27.6416 398.805 -1.70111 101.91 +EDGE_SE3:QUAT 1696 1697 5.24761 -0.303176 -0.339079 -0.00400076 0.0510769 0.000936178 0.998686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.41 -0.0180343 25.7753 398.952 1.18301 101.848 +EDGE_SE3:QUAT 1697 1698 5.31741 -0.07745 -0.215945 -0.000787542 0.0587911 -0.00173764 0.998268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.536 -0.0162309 29.7537 398.617 0.25367 102.448 +EDGE_SE3:QUAT 1698 1699 5.4001 -0.324897 -0.213265 -0.00116176 0.0561424 -0.00159851 0.998421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.133 -0.0165148 28.3824 398.739 0.362922 102.23 +EDGE_SE3:QUAT 1699 1700 5.31005 -0.212246 -0.0792141 -0.0032456 0.0571613 -0.0191679 0.998176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.264 -0.134932 28.8611 398.694 1.17544 102.273 +EDGE_SE3:QUAT 1700 1701 5.32973 -0.20021 -0.263265 -8.43428e-05 0.0550873 -0.0244532 0.998182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.971 -0.135834 27.8218 398.79 0.283929 102.084 +EDGE_SE3:QUAT 1701 1702 5.37667 -0.158821 -0.385745 0.00552104 0.055978 -0.0309868 0.997936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.121 -0.143423 28.3798 398.74 -1.31043 102.139 +EDGE_SE3:QUAT 1702 1703 5.37615 -0.269116 -0.350623 0.000403427 0.0585187 -0.00545235 0.998271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.494 -0.0314741 29.614 398.63 -0.059037 102.423 +EDGE_SE3:QUAT 1703 1704 5.21114 -0.263812 -0.0860465 -0.00227991 0.0472151 -0.0624556 0.996928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.858 -0.261486 23.6186 399.127 1.2558 101.165 +EDGE_SE3:QUAT 1704 1705 5.3006 -0.226295 -0.387647 -0.00417189 0.0523543 -0.0331095 0.998071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.546 -0.188151 26.3165 398.908 1.57783 101.82 +EDGE_SE3:QUAT 1705 1706 5.35171 -0.137301 -0.279671 0.00772626 0.0615781 -0.0138406 0.997976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.979 -0.0417477 31.2625 398.464 -2.13334 102.695 +EDGE_SE3:QUAT 1706 1707 5.34153 -0.227327 -0.349089 0.00565987 0.0526141 -0.0437893 0.997638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.642 -0.189399 26.6703 398.888 -1.24174 101.784 +EDGE_SE3:QUAT 1707 1708 5.15051 -0.193634 -0.419786 -0.00422146 0.0510518 -0.0433992 0.997744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.353 -0.227279 25.6007 398.966 1.68757 101.64 +EDGE_SE3:QUAT 1708 1709 5.3675 -0.434195 -0.228045 -0.0100084 0.057001 -0.0217349 0.998087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.169 -0.19144 28.6753 398.679 3.21535 102.265 +EDGE_SE3:QUAT 1709 1710 5.21468 -0.223632 -0.158705 0.00158348 0.0515878 -0.031705 0.998164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.484 -0.144823 26.0428 398.939 -0.155917 101.78 +EDGE_SE3:QUAT 1710 1711 5.35165 -0.192269 -0.328329 -0.00360188 0.054211 -0.0667013 0.996293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.751 -0.372995 27.1221 398.852 1.77264 101.605 +EDGE_SE3:QUAT 1711 1712 5.31447 -0.371108 -0.160969 -0.00918366 0.0457564 -0.0687302 0.996543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.563 -0.295489 22.5547 399.169 3.35885 100.982 +EDGE_SE3:QUAT 1712 1713 5.09853 -0.179806 -0.156039 0.00079486 0.0572315 -0.0341342 0.997777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.288 -0.199025 28.9322 398.697 0.137802 102.2 +EDGE_SE3:QUAT 1713 1714 5.22918 -0.340417 -0.245276 -0.00306265 0.0510218 -0.0413584 0.997836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.365 -0.211586 25.6249 398.968 1.32153 101.657 +EDGE_SE3:QUAT 1714 1715 5.34764 -0.145038 -0.320751 -0.00496787 0.0548876 -0.0102367 0.998428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.928 -0.0865245 27.7004 398.789 1.58687 102.124 +EDGE_SE3:QUAT 1715 1716 5.21627 -0.277662 -0.318961 0.0049549 0.0439147 -0.0276473 0.99864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.527 -0.0738725 22.1748 399.222 -1.24253 101.295 +EDGE_SE3:QUAT 1716 1717 5.46677 -0.192156 -0.254347 0.00225139 0.0589732 -0.0589002 0.996518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.547 -0.359363 29.8348 398.629 -0.00452786 102.113 +EDGE_SE3:QUAT 1717 1718 5.12361 -0.182455 -0.311828 -0.0004316 0.0482541 -0.0452611 0.997809 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.026 -0.193202 24.2666 399.079 0.553204 101.431 +EDGE_SE3:QUAT 1718 1719 5.15102 -0.340883 -0.248257 -0.000832086 0.059365 -0.0297499 0.997793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.609 -0.196968 30.0115 398.597 0.584575 102.403 +EDGE_SE3:QUAT 1719 1720 5.1014 -0.305378 -0.135992 -0.0102862 0.0540257 -0.0265324 0.998134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.72 -0.200609 27.0996 398.811 3.33946 102.004 +EDGE_SE3:QUAT 1720 1721 5.09683 -0.30535 -0.338787 -0.00283867 0.0620504 -0.0167051 0.997929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.041 -0.137792 31.4092 398.461 1.04008 102.701 +EDGE_SE3:QUAT 1721 1722 5.23714 -0.322653 -0.234773 0.000612509 0.0569028 -0.0319319 0.997869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.239 -0.184827 28.7615 398.711 0.166016 102.187 +EDGE_SE3:QUAT 1722 1723 5.22082 -0.117568 -0.246577 -0.0042507 0.0499658 -0.0352458 0.99812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.222 -0.181935 25.08 399.005 1.6087 101.631 +EDGE_SE3:QUAT 1723 1724 5.3624 -0.365673 -0.274439 0.00324338 0.0469593 -0.0422262 0.997999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.889 -0.15333 23.7074 399.12 -0.582093 101.383 +EDGE_SE3:QUAT 1724 1725 5.37723 -0.142066 -0.0682578 -3.53453e-05 0.0578309 -0.0362968 0.997666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.372 -0.221653 29.22 398.671 0.41243 102.231 +EDGE_SE3:QUAT 1725 1726 5.23363 -0.300123 -0.344702 0.00107671 0.0581726 -0.0402775 0.997493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.429 -0.241884 29.4164 398.656 0.128174 102.231 +EDGE_SE3:QUAT 1726 1727 5.28022 -0.266609 -0.314112 -0.0108285 0.0486769 -0.0201918 0.998552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.01 -0.143049 24.3939 399.024 3.41988 101.652 +EDGE_SE3:QUAT 1727 1728 5.25237 -0.14767 -0.327057 0.00271457 0.0507426 -0.022695 0.99845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.375 -0.0914715 25.6275 398.969 -0.586475 101.771 +EDGE_SE3:QUAT 1728 1729 5.41879 -0.238739 -0.181582 0.0056214 0.0546785 -0.0475559 0.997355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.935 -0.226781 27.7358 398.802 -1.17357 101.908 +EDGE_SE3:QUAT 1729 1730 5.38416 -0.108165 -0.258329 -0.00130348 0.0521063 -0.0252541 0.998321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.543 -0.132159 26.2664 398.918 0.642371 101.851 +EDGE_SE3:QUAT 1730 1731 5.27998 -0.339819 -0.244178 -0.0109944 0.0610195 -0.0293533 0.997644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.756 -0.273225 30.6785 398.49 3.60879 102.561 +EDGE_SE3:QUAT 1731 1732 5.20375 -0.172093 -0.143254 -0.00467506 0.0456248 -0.0247424 0.998641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.689 -0.115878 22.8945 399.166 1.6151 101.405 +EDGE_SE3:QUAT 1732 1733 5.36092 -0.113734 -0.209393 -0.00656149 0.0545008 -0.0176557 0.998336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.849 -0.134846 27.4543 398.804 2.13871 102.073 +EDGE_SE3:QUAT 1733 1734 5.00381 -0.183795 -0.27611 0.0124839 0.0480327 -0.0370039 0.998082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.025 -0.0917587 24.4639 399.028 -3.37852 101.561 +EDGE_SE3:QUAT 1734 1735 5.15945 -0.388414 -0.377163 -0.00419496 0.0482091 -0.0452217 0.997804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.983 -0.210723 24.1377 399.079 1.67544 101.424 +EDGE_SE3:QUAT 1735 1736 5.13365 -0.344961 -0.269009 -0.008939 0.0583643 -0.0592094 0.996498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.28 -0.4169 29.1006 398.651 3.32426 102.032 +EDGE_SE3:QUAT 1736 1737 5.34535 -0.355494 -0.313169 -0.00330297 0.0448651 -0.0604646 0.997156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.568 -0.2334 22.3917 399.21 1.51712 101.036 +EDGE_SE3:QUAT 1737 1738 5.1421 -0.149039 -0.236403 0.0044859 0.0477004 -0.0420123 0.997968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.987 -0.151478 24.1183 399.088 -0.948918 101.441 +EDGE_SE3:QUAT 1738 1739 5.26696 -0.210099 -0.538185 0.00264958 0.0491137 -0.0411375 0.997942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.159 -0.166742 24.7942 399.039 -0.398298 101.537 +EDGE_SE3:QUAT 1739 1740 5.11757 -0.240167 -0.202272 0.00207888 0.0458675 -0.0427866 0.998029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.75 -0.153494 23.1194 399.163 -0.238156 101.302 +EDGE_SE3:QUAT 1740 1741 5.09557 -0.261468 -0.226319 -0.00638859 0.0531163 -0.0351317 0.99795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.623 -0.215916 26.6503 398.871 2.26339 101.864 +EDGE_SE3:QUAT 1741 1742 5.1509 -0.31557 -0.33131 -0.00713292 0.05541 -0.03124 0.997949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.948 -0.217026 27.8386 398.768 2.45635 102.07 +EDGE_SE3:QUAT 1742 1743 5.05177 -0.271059 -0.220028 0.00100396 0.0512197 -0.0257758 0.998354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.434 -0.117546 25.8468 398.953 -0.0440992 101.786 +EDGE_SE3:QUAT 1743 1744 5.17976 -0.309352 -0.346285 -0.00277955 0.0483208 -0.0298412 0.998382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.03 -0.14068 24.2874 399.07 1.10895 101.553 +EDGE_SE3:QUAT 1744 1745 5.08443 -0.232754 -0.192742 -0.00778213 0.0523719 -0.00136768 0.998596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.566 -0.051861 26.4311 398.885 2.33206 101.955 +EDGE_SE3:QUAT 1745 1746 5.06282 -0.148988 -0.108716 -0.00207322 0.0501955 -0.0197386 0.998542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.286 -0.101736 25.2859 398.994 0.809726 101.738 +EDGE_SE3:QUAT 1746 1747 5.13999 -0.351509 -0.28481 -0.000923912 0.0503722 -0.0128009 0.998648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.318 -0.0642122 25.4001 398.986 0.400079 101.774 +EDGE_SE3:QUAT 1747 1748 5.10221 -0.208006 -0.111125 0.00168185 0.0494579 -0.0245647 0.998473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.203 -0.100372 24.9538 399.023 -0.266155 101.668 +EDGE_SE3:QUAT 1748 1749 5.19163 -0.316871 -0.0556211 -0.000468536 0.0474944 -0.059514 0.997097 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.917 -0.244856 23.8399 399.114 0.690629 101.226 +EDGE_SE3:QUAT 1749 1750 4.96233 -0.0370499 -0.338332 0.00599257 0.0549083 -0.0494949 0.997246 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.971 -0.237483 27.8675 398.792 -1.26154 101.909 +EDGE_SE3:QUAT 1750 1751 5.13469 -0.168774 -0.208992 -0.00972219 0.0514964 -0.0155009 0.998506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.403 -0.129177 25.8869 398.916 3.05125 101.867 +EDGE_SE3:QUAT 1751 1752 5.05912 -0.0357039 -0.0785567 -0.00745832 0.0537419 -0.0499982 0.997274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.662 -0.302048 26.8468 398.851 2.7412 101.775 +EDGE_SE3:QUAT 1752 1753 5.18405 -0.16026 -0.226098 0.000721675 0.0518893 -0.0371242 0.997962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.518 -0.177843 26.174 398.93 0.157112 101.762 +EDGE_SE3:QUAT 1753 1754 5.15883 -0.336766 -0.316554 0.00346974 0.0440955 -0.0379895 0.998299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.548 -0.118208 22.2501 399.222 -0.709105 101.233 +EDGE_SE3:QUAT 1754 1755 4.94534 -0.154155 -0.15906 0.00797737 0.0481879 -0.0437822 0.997846 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.058 -0.144922 24.4631 399.054 -1.96999 101.481 +EDGE_SE3:QUAT 1755 1756 5.02992 -0.316172 -0.225531 -0.00204207 0.0482993 -0.00551113 0.998816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.048 -0.0341192 24.3404 399.066 0.660602 101.644 +EDGE_SE3:QUAT 1756 1757 5.03435 -0.277086 -0.254374 0.00210127 0.0391224 -0.0535462 0.997796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.996 -0.140081 19.6835 399.394 -0.216481 100.792 +EDGE_SE3:QUAT 1757 1758 4.918 -0.183459 -0.33853 0.00212243 0.062378 -0.0155627 0.997929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.116 -0.0958256 31.632 398.443 -0.446188 102.739 +EDGE_SE3:QUAT 1758 1759 5.0202 -0.258962 -0.319223 0.0068398 0.0518093 -0.0531301 0.997219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.538 -0.223171 26.3064 398.92 -1.5064 101.642 +EDGE_SE3:QUAT 1759 1760 5.09639 -0.0864276 -0.231226 -0.00911088 0.0407002 -0.0348929 0.99852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.075 -0.141565 20.2488 399.322 3.00089 101.051 +EDGE_SE3:QUAT 1760 1761 5.11283 -0.375161 -0.165648 -0.0114209 0.0479246 -0.0437709 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.848 -0.236214 23.8005 399.061 3.81592 101.433 +EDGE_SE3:QUAT 1761 1762 5.16159 -0.228799 -0.251336 -0.00298299 0.0601385 -0.0547473 0.996683 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.669 -0.378699 30.2641 398.577 1.51673 102.24 +EDGE_SE3:QUAT 1762 1763 5.18125 -0.27907 -0.271409 0.001653 0.0493064 -0.0766234 0.995839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.151 -0.328855 24.8072 399.053 0.242754 101.12 +EDGE_SE3:QUAT 1763 1764 5.04027 -0.203104 -0.169254 0.0032318 0.0467858 -0.0391731 0.998131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.868 -0.139994 23.6178 399.126 -0.607861 101.397 +EDGE_SE3:QUAT 1764 1765 5.12174 -0.236564 -0.215704 -0.00205375 0.0572703 -0.0262234 0.998012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.281 -0.16989 28.9142 398.693 0.898687 102.248 +EDGE_SE3:QUAT 1765 1766 5.26865 -0.233047 -0.208571 -0.0024955 0.0530279 -0.0364747 0.997924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.65 -0.200504 26.6866 398.883 1.11666 101.846 +EDGE_SE3:QUAT 1766 1767 5.11228 -0.199159 -0.253987 0.000269335 0.0513677 -0.0433042 0.99774 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.44 -0.206145 25.8847 398.954 0.350067 101.671 +EDGE_SE3:QUAT 1767 1768 5.12173 -0.184384 -0.282995 -0.00804188 0.0426453 -0.0377874 0.998343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.293 -0.158574 21.2424 399.264 2.71746 101.138 +EDGE_SE3:QUAT 1768 1769 5.02767 -0.344458 -0.310333 -0.00744948 0.0544222 -0.0373948 0.99779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.788 -0.243937 27.2837 398.814 2.61073 101.947 +EDGE_SE3:QUAT 1769 1770 5.09559 -0.0512366 -0.271712 -0.00811118 0.0487968 -0.0536861 0.997332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.987 -0.269228 24.2656 399.05 2.92982 101.377 +EDGE_SE3:QUAT 1770 1771 5.11342 -0.280845 -0.207459 0.00451921 0.0495401 -0.0104603 0.998707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.212 -0.0222828 25.0107 399.012 -1.24699 101.73 +EDGE_SE3:QUAT 1771 1772 5.17651 -0.306526 -0.253489 -0.00209335 0.0501047 -0.0346173 0.998142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.26 -0.168891 25.2006 399.002 0.960105 101.646 +EDGE_SE3:QUAT 1772 1773 5.11425 -0.225281 -0.230751 0.00356415 0.0543662 -0.0206509 0.998301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.879 -0.0900033 27.5015 398.815 -0.845366 102.055 +EDGE_SE3:QUAT 1773 1774 4.94863 -0.196555 -0.208993 -0.00722747 0.0457117 -0.0263164 0.998582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.674 -0.13425 22.8905 399.155 2.39134 101.407 +EDGE_SE3:QUAT 1774 1775 5.06016 -0.20434 -0.0522081 -0.00199632 0.0508118 -0.0438181 0.997745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.344 -0.215737 25.5367 398.978 1.02639 101.621 +EDGE_SE3:QUAT 1775 1776 5.10048 -0.309485 -0.109571 -0.00165777 0.0523284 -0.031079 0.998145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.566 -0.164111 26.3608 398.91 0.807887 101.833 +EDGE_SE3:QUAT 1776 1777 4.98326 -0.158293 -0.304665 0.00651901 0.0498926 -0.041412 0.997874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.275 -0.153436 25.2919 398.995 -1.54352 101.61 +EDGE_SE3:QUAT 1777 1778 5.07 -0.171504 -0.110436 0.00101187 0.0566152 -0.0379423 0.997674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.195 -0.215554 28.6134 398.726 0.110962 102.122 +EDGE_SE3:QUAT 1778 1779 5.19136 -0.287359 -0.306423 0.00268159 0.0551059 -0.0438188 0.997515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.981 -0.226737 27.8716 398.792 -0.333996 101.959 +EDGE_SE3:QUAT 1779 1780 5.0023 -0.344019 -0.126438 0.000654388 0.0504088 -0.0455095 0.997691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.313 -0.206559 25.3996 398.994 0.249378 101.583 +EDGE_SE3:QUAT 1780 1781 5.0345 -0.482599 -0.148384 0.00577212 0.0510416 -0.0170723 0.998534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.414 -0.0488031 25.8088 398.947 -1.55184 101.826 +EDGE_SE3:QUAT 1781 1782 4.92071 -0.324862 -0.241897 0.00265819 0.0407366 -0.0485732 0.997985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.169 -0.135097 20.5218 399.34 -0.406382 100.936 +EDGE_SE3:QUAT 1782 1783 4.82176 -0.337135 -0.0834293 0.00749897 0.0468007 -0.00608145 0.998858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.849 0.0138461 23.6071 399.106 -2.18182 101.56 +EDGE_SE3:QUAT 1783 1784 5.05136 -0.257181 -0.317027 0.0010022 0.0507193 -0.0480472 0.997556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.355 -0.219179 25.5645 398.982 0.173264 101.582 +EDGE_SE3:QUAT 1784 1785 4.89393 -0.181988 -0.298799 0.000351047 0.0631066 -0.00669155 0.997984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 405.235 -0.0463052 31.9982 398.407 -0.0242275 102.822 +EDGE_SE3:QUAT 1785 1786 5.0384 -0.128486 -0.212315 0.00818264 0.0498299 -0.0406233 0.997898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.269 -0.140648 25.2995 398.988 -2.04767 101.623 +EDGE_SE3:QUAT 1786 1787 5.02545 -0.460312 -0.180722 -0.00930562 0.0430006 -0.0107152 0.998974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.364 -0.0784015 21.5747 399.237 2.86856 101.311 +EDGE_SE3:QUAT 1787 1788 4.83218 -0.198488 -0.344257 -0.00135935 0.0494278 -0.0345518 0.998179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.178 -0.160374 24.8698 399.029 0.736445 101.599 +EDGE_SE3:QUAT 1788 1789 4.90438 -0.208304 -0.292683 -0.00831218 0.0416256 -0.0272528 0.998727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.196 -0.120989 20.7846 399.293 2.7051 101.153 +EDGE_SE3:QUAT 1789 1790 5.09904 -0.261975 -0.275921 -0.00188217 0.0510673 -0.0410407 0.99785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.383 -0.204322 25.6798 398.966 0.966733 101.664 +EDGE_SE3:QUAT 1790 1791 4.92126 -0.296514 -0.183025 0.000845935 0.0460381 -0.0485018 0.997761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.76 -0.182302 23.1656 399.161 0.18274 101.256 +EDGE_SE3:QUAT 1791 1792 4.92158 -0.187052 -0.278332 0.00024092 0.0446818 -0.0244958 0.998701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.606 -0.0876252 22.489 399.204 0.141392 101.346 +EDGE_SE3:QUAT 1792 1793 4.98289 -0.235286 -0.136228 0.00441943 0.0530638 -0.0696597 0.996149 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.691 -0.333249 26.8656 398.889 -0.602074 101.514 +EDGE_SE3:QUAT 1793 1794 4.95651 -0.211982 -0.330773 -0.00510291 0.0548355 -0.0241025 0.998191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.9 -0.162541 27.6159 398.796 1.77344 102.066 +EDGE_SE3:QUAT 1794 1795 4.90502 -0.40185 -0.176247 0.00461669 0.0588953 -0.0525391 0.99687 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.562 -0.303865 29.8834 398.62 -0.781261 102.194 +EDGE_SE3:QUAT 1795 1796 4.98873 -0.090772 -0.125356 0.00351331 0.0482874 -0.0450526 0.997811 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.057 -0.173309 24.394 399.07 -0.625513 101.45 +EDGE_SE3:QUAT 1796 1797 4.75329 -0.0154757 -0.10417 0.00302598 0.0491825 -0.0368063 0.998107 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.17 -0.14619 24.8386 399.034 -0.551424 101.577 +EDGE_SE3:QUAT 1797 1798 4.92674 -0.109837 -0.138109 0.0107611 0.0473484 -0.0579487 0.997138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.966 -0.185165 24.1705 399.072 -2.67736 101.308 +EDGE_SE3:QUAT 1798 1799 4.90501 -0.347689 -0.231813 0.00615354 0.0488381 -0.0675519 0.996501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.141 -0.263308 24.7769 399.048 -1.19435 101.25 +EDGE_SE3:QUAT 1799 1800 4.77922 -0.223 -0.165329 -0.00203555 0.0455179 -0.0371368 0.998271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.684 -0.148956 22.8489 399.177 0.937061 101.316 +EDGE_SE3:QUAT 1800 1801 5.09266 -0.282487 -0.304662 -0.00582833 0.0518485 0.00781009 0.998607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.515 0.00493593 26.1961 398.914 1.65837 101.906 +EDGE_SE3:QUAT 1801 1802 4.97544 -0.211475 -0.223103 0.00338524 0.0473305 -0.0954072 0.994307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.907 -0.371276 23.85 399.136 -0.126498 100.667 +EDGE_SE3:QUAT 1802 1803 4.77412 -0.318084 0.0552795 -0.00758613 0.045377 -0.014866 0.998831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.648 -0.0922285 22.7773 399.162 2.39538 101.44 +EDGE_SE3:QUAT 1803 1804 4.80861 -0.26475 -0.388229 -0.00579221 0.0416062 -0.051863 0.99777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.185 -0.184848 20.6926 399.312 2.15423 100.939 +EDGE_SE3:QUAT 1804 1805 4.88532 -0.165758 -0.228279 -0.00135509 0.0486738 -0.0234618 0.998538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.089 -0.108098 24.5077 399.055 0.625563 101.614 +EDGE_SE3:QUAT 1805 1806 4.9284 -0.132573 -0.231986 -0.00487647 0.0566077 -0.0215887 0.998151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.166 -0.156629 28.5448 398.717 1.6854 102.219 +EDGE_SE3:QUAT 1806 1807 4.77373 -0.360763 -0.212926 0.00299469 0.0472925 -0.0415684 0.998011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.929 -0.154155 23.8713 399.108 -0.511294 101.41 +EDGE_SE3:QUAT 1807 1808 4.85952 -0.260821 -0.139659 -0.00439634 0.0450539 -0.0720509 0.996373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.556 -0.280324 22.3832 399.209 1.94943 100.887 +EDGE_SE3:QUAT 1808 1809 4.82634 -0.171044 -0.203148 -0.00765704 0.0474211 -0.0234993 0.998569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.882 -0.134314 23.7733 399.089 2.50078 101.536 +EDGE_SE3:QUAT 1809 1810 4.95183 -0.208995 -0.101037 -0.00652816 0.0490407 -0.0489569 0.997575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.052 -0.244782 24.4737 399.043 2.41407 101.444 +EDGE_SE3:QUAT 1810 1811 4.79758 -0.32531 -0.122337 0.002129 0.0520416 -0.0459111 0.997587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.543 -0.214541 26.2785 398.925 -0.172694 101.703 +EDGE_SE3:QUAT 1811 1812 4.91477 -0.120461 -0.40838 -0.00899682 0.0479742 -0.00212878 0.998806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.975 -0.0558281 24.1678 399.056 2.70298 101.646 +EDGE_SE3:QUAT 1812 1813 4.81165 -0.271805 -0.288145 0.000132818 0.0479589 -0.0324568 0.998322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.001 -0.134912 24.1528 399.085 0.262648 101.515 +EDGE_SE3:QUAT 1813 1814 5.01526 -0.396095 -0.225831 0.00545685 0.0517284 -0.037397 0.997946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.517 -0.15219 26.2008 398.924 -1.25251 101.768 +EDGE_SE3:QUAT 1814 1815 4.87234 -0.130062 -0.269351 -0.0103165 0.0535824 -0.0114793 0.998444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.694 -0.120867 26.9825 398.823 3.19074 102.04 +EDGE_SE3:QUAT 1815 1816 4.88553 -0.28768 -0.145095 -0.00111067 0.0467299 -0.0394391 0.998128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.836 -0.161477 23.4835 399.134 0.69014 101.378 +EDGE_SE3:QUAT 1816 1817 4.75327 -0.0974786 -0.203379 0.00564999 0.0429839 -0.0743987 0.996286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.43 -0.226267 21.7792 399.265 -1.06118 100.767 +EDGE_SE3:QUAT 1817 1818 4.7098 -0.268331 -0.263478 0.0112114 0.0440364 -0.0436215 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.549 -0.102741 22.4287 399.185 -2.97261 101.236 +EDGE_SE3:QUAT 1818 1819 4.82591 -0.266342 -0.438479 0.00481539 0.0428828 -0.0593623 0.997303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.415 -0.1776 21.6855 399.266 -0.940199 100.957 +EDGE_SE3:QUAT 1819 1820 4.83841 -0.161507 -0.0770926 -0.00104909 0.0514227 -0.0497036 0.997439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.429 -0.243898 25.8588 398.956 0.807611 101.61 +EDGE_SE3:QUAT 1820 1821 4.97919 -0.447477 -0.280722 0.00133685 0.0368716 -0.0546667 0.997823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.768 -0.129358 18.5177 399.463 -0.00270482 100.656 +EDGE_SE3:QUAT 1821 1822 4.85974 -0.317102 -0.480157 0.0107548 0.0499591 -0.0222424 0.998446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.259 -0.0426268 25.3339 398.965 -2.99089 101.76 +EDGE_SE3:QUAT 1822 1823 4.83929 -0.238797 -0.319069 0.00312884 0.0495197 -0.0596203 0.996987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.208 -0.2498 25.0069 399.03 -0.359865 101.379 +EDGE_SE3:QUAT 1823 1824 4.78394 -0.403704 -0.205208 -0.00201729 0.0566427 -0.085603 0.994716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.085 -0.505017 28.3367 398.767 1.53824 101.498 +EDGE_SE3:QUAT 1824 1825 4.81702 -0.348762 -0.265972 -0.00535325 0.0544408 -0.0286029 0.998093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.833 -0.185761 27.3874 398.814 1.8938 102.009 +EDGE_SE3:QUAT 1825 1826 4.81675 -0.24492 -0.117994 -0.000611018 0.0485112 -0.0394612 0.998043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.062 -0.171595 24.4063 399.066 0.553959 101.499 +EDGE_SE3:QUAT 1826 1827 4.89557 -0.361056 -0.307536 -0.000688206 0.046097 -0.0338191 0.998364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.766 -0.133665 23.1819 399.155 0.50889 101.38 +EDGE_SE3:QUAT 1827 1828 4.75582 -0.271349 -0.15809 -0.00102968 0.0449574 -0.0560116 0.997417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.609 -0.209015 22.5373 399.205 0.799537 101.1 +EDGE_SE3:QUAT 1828 1829 4.73049 -0.294431 -0.301175 0.00321142 0.0415045 -0.0833581 0.99565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.243 -0.24697 20.9085 399.328 -0.27924 100.52 +EDGE_SE3:QUAT 1829 1830 4.92886 -0.130165 -0.165002 -0.000860371 0.0581997 -0.0166803 0.998165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.438 -0.108859 29.4314 398.647 0.441434 102.369 +EDGE_SE3:QUAT 1830 1831 4.6298 -0.435083 -0.137867 0.000508491 0.0468127 -0.0319853 0.998391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.861 -0.124758 23.5747 399.128 0.139444 101.442 +EDGE_SE3:QUAT 1831 1832 4.74803 -0.151841 -0.288237 0.00623271 0.0508371 -0.041159 0.997839 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.4 -0.160248 25.7685 398.958 -1.45314 101.678 +EDGE_SE3:QUAT 1832 1833 4.85339 -0.343561 -0.169301 0.00137562 0.0491954 -0.0444536 0.997798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.16 -0.188338 24.7998 399.04 0.014066 101.509 +EDGE_SE3:QUAT 1833 1834 4.54808 -0.392319 -0.214532 -0.00694118 0.0476651 -0.0138035 0.998744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.934 -0.0925754 23.9585 399.08 2.19813 101.592 +EDGE_SE3:QUAT 1834 1835 4.64417 -0.311206 -0.476396 -0.00181451 0.0483315 -0.0201986 0.998625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.045 -0.0951861 24.3326 399.067 0.730523 101.605 +EDGE_SE3:QUAT 1835 1836 4.95349 -0.223524 -0.261534 -0.00315404 0.0472221 -0.0171346 0.998732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.901 -0.0854023 23.7563 399.107 1.09807 101.543 +EDGE_SE3:QUAT 1836 1837 4.70114 -0.124719 -0.272527 -0.00296745 0.0514601 -0.0469444 0.997567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.417 -0.241042 25.8299 398.953 1.35228 101.637 +EDGE_SE3:QUAT 1837 1838 4.62714 -0.201168 -0.165333 -0.00410758 0.0540077 -0.0162952 0.998399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.8 -0.111038 27.2327 398.831 1.39251 102.035 +EDGE_SE3:QUAT 1838 1839 4.77426 -0.113355 -0.322589 -0.00500273 0.0474494 -0.0454535 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.879 -0.209009 23.7256 399.106 1.91265 101.37 +EDGE_SE3:QUAT 1839 1840 4.61616 -0.293992 -0.216557 0.00297828 0.0441917 -0.0606345 0.997177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.552 -0.201503 22.2833 399.227 -0.365502 101.012 +EDGE_SE3:QUAT 1840 1841 4.67614 -0.295208 -0.313561 0.000741565 0.0588232 -0.0448415 0.997261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.523 -0.278275 29.7358 398.629 0.284019 102.244 +EDGE_SE3:QUAT 1841 1842 4.61225 -0.179533 -0.271756 -0.00522949 0.0573979 -0.0381143 0.99761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.251 -0.26069 28.8671 398.689 1.97561 102.175 +EDGE_SE3:QUAT 1842 1843 4.76378 -0.377619 -0.214941 0.00363609 0.0431782 -0.0364544 0.998395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.443 -0.107052 21.7855 399.253 -0.778415 101.188 +EDGE_SE3:QUAT 1843 1844 4.75419 -0.359341 -0.170499 0.000157608 0.04754 -0.0589502 0.997128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.929 -0.240252 23.8877 399.112 0.498929 101.238 +EDGE_SE3:QUAT 1844 1845 4.68768 -0.252698 -0.156315 0.0018749 0.0501584 -0.104345 0.993274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.228 -0.463371 25.1665 399.044 0.46422 100.667 +EDGE_SE3:QUAT 1845 1846 4.72071 -0.0861133 -0.295451 0.00142568 0.050374 -0.0273163 0.998356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.322 -0.118415 25.4188 398.987 -0.158772 101.718 +EDGE_SE3:QUAT 1846 1847 4.5354 -0.407092 -0.101975 -0.00401327 0.046069 -0.00933466 0.998887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.762 -0.0558975 23.1812 399.147 1.28114 101.49 +EDGE_SE3:QUAT 1847 1848 4.60801 -0.126293 -0.244688 -0.000184256 0.0519774 -0.0471141 0.997536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.515 -0.232121 26.1765 398.932 0.528494 101.679 +EDGE_SE3:QUAT 1848 1849 4.61804 -0.109776 0.0579462 0.006525 0.049884 -0.0352321 0.998112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.271 -0.124971 25.2737 398.993 -1.60509 101.656 +EDGE_SE3:QUAT 1849 1850 4.77603 -0.15837 -0.10548 0.00236647 0.0518958 -0.0375793 0.997942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.528 -0.171147 26.2152 398.927 -0.328491 101.764 +EDGE_SE3:QUAT 1850 1851 4.63142 -0.272999 -0.128289 0.00481592 0.0393709 -0.0541505 0.997745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.035 -0.133354 19.8989 399.378 -1.02091 100.812 +EDGE_SE3:QUAT 1851 1852 4.68181 -0.0973537 -0.151376 -0.00101235 0.0496031 -0.0456479 0.997725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.193 -0.208837 24.9394 399.027 0.741214 101.52 +EDGE_SE3:QUAT 1852 1853 4.6503 -0.320069 -0.331807 -0.00144811 0.0506309 -0.0674056 0.996439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.295 -0.319048 25.3754 399 1.09509 101.336 +EDGE_SE3:QUAT 1853 1854 4.69398 -0.193299 0.0197714 -0.00861098 0.045504 -0.00362178 0.99892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.672 -0.0558305 22.8967 399.15 2.60172 101.479 +EDGE_SE3:QUAT 1854 1855 4.6655 -0.267701 -0.190265 -0.000454785 0.0432824 -0.0138616 0.998967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.446 -0.0492271 21.7761 399.251 0.252864 101.3 +EDGE_SE3:QUAT 1855 1856 4.42177 -0.256342 -0.205254 -0.00616202 0.0478035 -0.0467551 0.997743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.906 -0.222642 23.8659 399.09 2.27366 101.382 +EDGE_SE3:QUAT 1856 1857 4.71076 -0.367691 -0.227541 -0.00670435 0.0564998 0.000717589 0.99838 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 404.169 -0.0383525 28.5702 398.71 1.98707 102.273 +EDGE_SE3:QUAT 1857 1858 4.50405 -0.294668 -0.26997 -0.00760307 0.050846 -0.0318554 0.998169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.307 -0.190203 25.4782 398.959 2.5799 101.723 +EDGE_SE3:QUAT 1858 1859 4.55554 -0.148973 -0.182055 0.000646642 0.0453039 0.0176613 0.998817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.679 0.068957 22.802 399.18 -0.348768 101.414 +EDGE_SE3:QUAT 1859 1860 4.64651 -0.277451 -0.359388 -0.00310871 0.0540635 -0.0278338 0.998145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.801 -0.166331 27.2364 398.835 1.21551 101.983 +EDGE_SE3:QUAT 1860 1861 4.56676 -0.36899 -0.164651 0.00434733 0.042009 -0.0345322 0.998511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.313 -0.0916259 21.2037 399.29 -1.01489 101.134 +EDGE_SE3:QUAT 1861 1862 4.50337 -0.230667 -0.177172 0.00408725 0.0458116 -0.0557518 0.997385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.752 -0.193534 23.1491 399.164 -0.722038 101.179 +EDGE_SE3:QUAT 1862 1863 4.64065 -0.300941 -0.158616 -0.003345 0.0455454 -0.0460198 0.997896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.666 -0.187893 22.7987 399.179 1.40752 101.24 +EDGE_SE3:QUAT 1863 1864 4.59642 -0.254075 -0.0463375 0.0114519 0.0392916 -0.0747211 0.996364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.054 -0.167714 20.173 399.347 -2.8468 100.598 +EDGE_SE3:QUAT 1864 1865 4.63337 -0.209633 -0.260197 -0.00589239 0.0447671 -0.00590059 0.998963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.6 -0.0497988 22.5185 399.189 1.81018 101.417 +EDGE_SE3:QUAT 1865 1866 4.42479 -0.240782 -0.264261 -0.000755036 0.0511822 -0.0440849 0.997716 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.405 -0.213675 25.7599 398.963 0.661808 101.648 +EDGE_SE3:QUAT 1866 1867 4.55391 -0.261659 -0.358861 0.000379057 0.0404325 -0.0406187 0.998356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.127 -0.118582 20.311 399.351 0.208718 100.983 +EDGE_SE3:QUAT 1867 1868 4.55404 -0.030304 -0.261655 0.00821557 0.0433422 -0.0617539 0.997116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.482 -0.17579 22.0487 399.234 -1.93047 100.981 +EDGE_SE3:QUAT 1868 1869 4.59594 -0.359304 -0.28261 -0.00199654 0.0465214 -0.0173548 0.998765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.821 -0.0781814 23.4099 399.135 0.752658 101.495 +EDGE_SE3:QUAT 1869 1870 4.78738 -0.167502 -0.151601 0.00321895 0.0447438 -0.0499976 0.997741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.621 -0.166958 22.5766 399.203 -0.524451 101.167 +EDGE_SE3:QUAT 1870 1871 4.56802 -0.129037 -0.20308 0.00392832 0.0488667 -0.055879 0.997233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.131 -0.222928 24.7033 399.051 -0.641357 101.382 +EDGE_SE3:QUAT 1871 1872 4.48885 -0.0342608 -0.0181551 0.0107473 0.0373773 -0.0296801 0.998803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.816 -0.0333932 18.9585 399.404 -2.99503 100.942 +EDGE_SE3:QUAT 1872 1873 4.3311 -0.264852 -0.186083 -0.00207168 0.0522587 -0.0658541 0.996458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.506 -0.335467 26.1891 398.933 1.28478 101.474 +EDGE_SE3:QUAT 1873 1874 4.49719 -0.261598 0.0532623 0.00277608 0.0460476 -0.0469369 0.997832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.775 -0.16751 23.2288 399.157 -0.407497 101.279 +EDGE_SE3:QUAT 1874 1875 4.58532 -0.23031 -0.192696 0.000268244 0.0508194 -0.053674 0.997264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.357 -0.249985 25.5811 398.982 0.448731 101.528 +EDGE_SE3:QUAT 1875 1876 4.35546 -0.339718 -0.169654 -0.0036272 0.0406909 -0.0457312 0.998118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.12 -0.151175 20.3224 399.343 1.44908 100.948 +EDGE_SE3:QUAT 1876 1877 4.54031 -0.244959 -0.267222 0.00246873 0.038051 -0.0331321 0.998723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.893 -0.0772346 19.153 399.421 -0.49042 100.912 +EDGE_SE3:QUAT 1877 1878 4.60547 -0.309716 -0.251823 0.00128472 0.0477875 -0.0891435 0.994871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.941 -0.360809 23.9791 399.121 0.449869 100.801 +EDGE_SE3:QUAT 1878 1879 4.54325 -0.115893 -0.140441 -0.00528789 0.0491716 -0.0414223 0.997917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.098 -0.20809 24.619 399.037 1.97257 101.525 +EDGE_SE3:QUAT 1879 1880 4.52617 -0.302251 -0.37575 0.00336281 0.0539942 -0.0788941 0.995414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.802 -0.39963 27.2814 398.862 -0.177828 101.438 +EDGE_SE3:QUAT 1880 1881 4.54856 -0.158533 -0.254646 0.00351937 0.0495754 -0.0502132 0.997501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.221 -0.206328 25.0533 399.022 -0.566686 101.49 +EDGE_SE3:QUAT 1881 1882 4.35954 -0.288155 -0.211167 0.00516804 0.0417294 -0.0347028 0.998513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.284 -0.087289 21.079 399.297 -1.26054 101.12 +EDGE_SE3:QUAT 1882 1883 4.56887 -0.0929468 -0.311223 0.00411054 0.0434269 -0.0889099 0.995084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.461 -0.286828 21.9225 399.264 -0.469773 100.544 +EDGE_SE3:QUAT 1883 1884 4.46033 -0.294934 -0.219197 0.00540274 0.0510826 -0.0500466 0.997425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.432 -0.209098 25.8838 398.955 -1.11582 101.61 +EDGE_SE3:QUAT 1884 1885 4.38959 -0.196717 -0.208776 0.00566222 0.0465276 -0.0545421 0.997411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.847 -0.187919 23.5669 399.132 -1.19567 101.249 +EDGE_SE3:QUAT 1885 1886 4.43024 -0.160032 -0.239509 -0.0146545 0.0462176 -0.0607662 0.996974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.529 -0.294591 22.6484 399.114 4.92521 101.141 +EDGE_SE3:QUAT 1886 1887 4.50574 -0.253492 -0.131022 -0.00192422 0.0456006 -0.0267331 0.9986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.703 -0.110102 22.9201 399.171 0.811672 101.391 +EDGE_SE3:QUAT 1887 1888 4.51343 -0.429701 -0.287934 0.00395063 0.0539818 -0.0748023 0.995728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.811 -0.374988 27.3099 398.856 -0.396467 101.505 +EDGE_SE3:QUAT 1888 1889 4.47962 -0.37622 -0.272483 -0.00252416 0.0407804 -0.0346235 0.998565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.149 -0.114635 20.433 399.338 1.03089 101.046 +EDGE_SE3:QUAT 1889 1890 4.34179 -0.0240087 -0.241593 0.0056707 0.0485706 -0.0420665 0.997917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.101 -0.151727 24.5942 399.05 -1.29488 101.507 +EDGE_SE3:QUAT 1890 1891 4.35205 -0.16348 -0.20882 -0.00501982 0.0437657 -0.0256323 0.9987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.468 -0.111905 21.9371 399.231 1.71779 101.283 +EDGE_SE3:QUAT 1891 1892 4.30193 -0.281841 -0.088496 -0.00109444 0.0467132 -0.0784287 0.995824 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.79 -0.312288 23.3488 399.155 1.04365 100.903 +EDGE_SE3:QUAT 1892 1893 4.21476 -0.111473 -0.192084 -0.00789314 0.0370098 -0.029968 0.998834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.726 -0.103506 18.4329 399.44 2.57832 100.88 +EDGE_SE3:QUAT 1893 1894 4.4421 -0.337322 -0.22283 -1.27213e-05 0.0411714 -0.0103768 0.999098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.213 -0.03196 20.7063 399.322 0.087358 101.182 +EDGE_SE3:QUAT 1894 1895 4.38043 -0.385174 -0.169445 0.00519922 0.0503714 -0.0469374 0.997613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.335 -0.189463 25.5101 398.983 -1.09224 101.588 +EDGE_SE3:QUAT 1895 1896 4.31434 -0.270794 -0.282302 0.00292983 0.0449191 -0.0384076 0.998248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.642 -0.127005 22.6575 399.194 -0.538277 101.28 +EDGE_SE3:QUAT 1896 1897 4.44356 -0.29539 -0.240215 -0.0053698 0.0420813 -0.0405157 0.998278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.258 -0.152204 21.0052 399.293 1.93807 101.077 +EDGE_SE3:QUAT 1897 1898 4.46323 -0.226667 -0.147095 0.00910984 0.0343558 -0.060677 0.997524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.559 -0.0997464 17.5268 399.504 -2.31444 100.504 +EDGE_SE3:QUAT 1898 1899 4.31549 -0.306274 -0.332723 0.0073944 0.0470011 -0.0410765 0.998023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.906 -0.128757 23.8333 399.102 -1.83094 101.419 +EDGE_SE3:QUAT 1899 1900 4.18451 -0.150939 -0.40337 0.000343894 0.0438374 -0.0235357 0.998761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.509 -0.0804793 22.0606 399.233 0.0985925 101.298 +EDGE_SE3:QUAT 1900 1901 4.3209 -0.0123597 -0.102028 0.00122526 0.0460728 -0.0254944 0.998612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.775 -0.0923043 23.2139 399.153 -0.137115 101.432 +EDGE_SE3:QUAT 1901 1902 4.319 -0.192356 -0.0337542 -0.00743524 0.0420077 -0.0400596 0.998286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.227 -0.158743 20.9187 399.288 2.55089 101.08 +EDGE_SE3:QUAT 1902 1903 4.41828 -0.0962022 -0.211985 -0.00291394 0.0374417 -0.0549809 0.997781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.789 -0.149008 18.6628 399.448 1.27717 100.674 +EDGE_SE3:QUAT 1903 1904 4.25658 -0.12072 -0.0793969 0.00276641 0.0481385 -0.00408183 0.998828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.031 -0.00271021 24.2722 399.071 -0.78693 101.636 +EDGE_SE3:QUAT 1904 1905 4.25253 -0.242802 -0.268575 0.00709083 0.0469899 -0.0302426 0.998412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.897 -0.0860147 23.7894 399.102 -1.83937 101.491 +EDGE_SE3:QUAT 1905 1906 4.49917 -0.266086 -0.377066 -0.00299264 0.0478204 -0.0960338 0.994224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.862 -0.40348 23.7188 399.13 1.7948 100.651 +EDGE_SE3:QUAT 1906 1907 4.31382 -0.267079 -0.208264 0.00243467 0.0445596 -0.0572196 0.997364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.592 -0.194993 22.4534 399.215 -0.228819 101.073 +EDGE_SE3:QUAT 1907 1908 4.45144 -0.365909 -0.312542 -0.00442867 0.0448525 -0.0558602 0.997421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.559 -0.221736 22.3668 399.207 1.81245 101.091 +EDGE_SE3:QUAT 1908 1909 4.26669 -0.274093 -0.135733 -0.00462716 0.044682 -0.045748 0.997942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.551 -0.18562 22.3234 399.207 1.78092 101.188 +EDGE_SE3:QUAT 1909 1910 4.24691 -0.11138 -0.14229 0.00138556 0.0428652 -0.0296125 0.998641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.401 -0.0924768 21.5789 399.267 -0.165822 101.207 +EDGE_SE3:QUAT 1910 1911 4.22629 -0.253439 -0.157639 0.0028849 0.0406952 -0.0380103 0.998444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.167 -0.102048 20.5061 399.338 -0.558975 101.026 +EDGE_SE3:QUAT 1911 1912 4.2983 -0.148176 -0.101345 -0.00110823 0.0348779 -0.0563736 0.9978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.564 -0.127025 17.4244 399.522 0.71997 100.53 +EDGE_SE3:QUAT 1912 1913 4.29847 -0.247014 -0.216417 0.00607226 0.0443799 -0.0838186 0.995474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.591 -0.274522 22.5116 399.22 -1.085 100.707 +EDGE_SE3:QUAT 1913 1914 4.28744 -0.190456 -0.1246 0.000312447 0.0442881 -0.0658632 0.996845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.536 -0.231752 22.2202 399.232 0.477742 100.939 +EDGE_SE3:QUAT 1914 1915 4.26013 -0.293275 -0.118631 0.00276752 0.0419456 -0.0465547 0.998031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.301 -0.136676 21.1396 399.299 -0.444495 101.027 +EDGE_SE3:QUAT 1915 1916 4.29278 -0.211865 -0.419779 -0.000154591 0.046327 -0.0521472 0.997564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.784 -0.203253 23.2748 399.153 0.517133 101.234 +EDGE_SE3:QUAT 1916 1917 4.43892 -0.212728 -0.157385 0.00320782 0.0433787 -0.0882965 0.995144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.446 -0.287161 21.8499 399.269 -0.205904 100.546 +EDGE_SE3:QUAT 1917 1918 4.24089 -0.232276 -0.177805 -0.00506192 0.0259007 -0.0602378 0.997835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.826 -0.0837552 12.7532 399.732 1.82758 100.103 +EDGE_SE3:QUAT 1918 1919 4.16527 -0.25614 -0.129577 -0.0025459 0.0370308 -0.0223415 0.999061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.777 -0.0651489 18.5612 399.452 0.923799 100.913 +EDGE_SE3:QUAT 1919 1920 4.2376 -0.208001 -0.244516 0.00340392 0.0327629 -0.0642523 0.99739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.405 -0.114024 16.5141 399.573 -0.602313 100.348 +EDGE_SE3:QUAT 1920 1921 4.26588 -0.244314 -0.138584 0.0114274 0.0455118 -0.064925 0.996786 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.747 -0.193677 23.288 399.136 -2.83529 101.109 +EDGE_SE3:QUAT 1921 1922 4.29202 -0.326796 -0.249091 0.00695701 0.0437835 -0.0448389 0.99801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.522 -0.124912 22.1899 399.221 -1.69414 101.176 +EDGE_SE3:QUAT 1922 1923 4.17805 -0.216368 -0.262239 -0.00416437 0.0499745 -0.0229748 0.998478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.24 -0.126647 25.1349 399.001 1.46379 101.708 +EDGE_SE3:QUAT 1923 1924 4.27869 -0.319575 -0.233288 -0.00999166 0.0397428 -0.0449528 0.998148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.946 -0.166157 19.6673 399.352 3.33773 100.914 +EDGE_SE3:QUAT 1924 1925 4.29058 -0.376121 -0.384833 0.00201736 0.0469225 -0.0559982 0.997326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.872 -0.213952 23.6442 399.13 -0.0901671 101.239 +EDGE_SE3:QUAT 1925 1926 4.39244 -0.23956 0.0539397 -0.00245889 0.0425265 -0.0636011 0.997066 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.31 -0.216773 21.2224 399.292 1.26547 100.854 +EDGE_SE3:QUAT 1926 1927 4.19606 -0.34414 -0.142735 -0.00246053 0.0421448 -0.03317 0.998558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.298 -0.117293 21.1322 399.293 1.00845 101.136 +EDGE_SE3:QUAT 1927 1928 4.30325 -0.266877 -0.14374 -0.00503444 0.0415572 -0.0264996 0.998772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.221 -0.104492 20.8087 399.306 1.71943 101.145 +EDGE_SE3:QUAT 1928 1929 4.19134 -0.324255 -0.178556 -0.00637574 0.0444495 -0.0394178 0.998213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.514 -0.169423 22.1912 399.208 2.24587 101.232 +EDGE_SE3:QUAT 1929 1930 4.09887 -0.297373 -0.32448 0.00262444 0.0378949 -0.0342513 0.998691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.878 -0.0788859 19.0775 399.426 -0.529629 100.897 +EDGE_SE3:QUAT 1930 1931 4.23549 -0.303304 -0.379125 0.00391034 0.0385818 -0.0406929 0.998419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.95 -0.094426 19.4596 399.402 -0.860639 100.891 +EDGE_SE3:QUAT 1931 1932 4.08328 -0.391529 -0.19426 -0.00433739 0.0363474 -0.0470139 0.998223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.679 -0.127035 18.0961 399.475 1.6342 100.701 +EDGE_SE3:QUAT 1932 1933 4.06086 -0.167069 -0.0924443 -0.00725426 0.043736 -0.0425392 0.998111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.417 -0.178521 21.7871 399.232 2.53026 101.162 +EDGE_SE3:QUAT 1933 1934 4.15542 -0.178941 -0.0754697 -0.00639257 0.0444651 -0.0594579 0.99722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.481 -0.238234 22.0789 399.218 2.42698 101.023 +EDGE_SE3:QUAT 1934 1935 4.28579 -0.482084 -0.197275 0.00112022 0.0372588 -0.0380818 0.998579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.81 -0.0913859 18.7215 399.448 -0.0559348 100.831 +EDGE_SE3:QUAT 1935 1936 4.3514 -0.266014 -0.196074 -0.00416278 0.0387832 -0.0458094 0.998188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.918 -0.139984 19.3394 399.403 1.59383 100.841 +EDGE_SE3:QUAT 1936 1937 4.12983 -0.285903 -0.183014 0.0101046 0.027697 -0.0400393 0.998763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.995 -0.0274971 14.1096 399.66 -2.80622 100.421 +EDGE_SE3:QUAT 1937 1938 4.21764 -0.27165 -0.0621017 0.00104672 0.0422675 -0.0708627 0.99659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.312 -0.224052 21.2137 399.302 0.275271 100.749 +EDGE_SE3:QUAT 1938 1939 4.08981 -0.344466 -0.0921311 -0.0120848 0.0383529 -0.028222 0.998793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.809 -0.121659 19.0499 399.376 3.82511 100.981 +EDGE_SE3:QUAT 1939 1940 3.9116 -0.223302 -0.244041 -0.00178134 0.0321424 -0.0179331 0.999321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.341 -0.0393556 16.1052 399.587 0.646815 100.693 +EDGE_SE3:QUAT 1940 1941 4.26428 -0.17288 -0.229269 0.00508842 0.0513039 -0.0579715 0.996986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.459 -0.251021 25.992 398.951 -0.941069 101.539 +EDGE_SE3:QUAT 1941 1942 4.15675 -0.219201 -0.266267 0.00218551 0.0363046 -0.0677135 0.997042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.715 -0.153498 18.2501 399.481 -0.168541 100.469 +EDGE_SE3:QUAT 1942 1943 4.14824 -0.308997 -0.252387 0.00162089 0.0452009 -0.0426586 0.998065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.668 -0.150522 22.7673 399.188 -0.107894 101.258 +EDGE_SE3:QUAT 1943 1944 4.25728 -0.188387 -0.156685 -0.00298454 0.036822 -0.0559316 0.997751 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.728 -0.146719 18.3434 399.466 1.29888 100.631 +EDGE_SE3:QUAT 1944 1945 4.02996 -0.35726 -0.0912853 0.00410584 0.0475246 -0.0663644 0.996655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.959 -0.252748 24.0218 399.106 -0.610852 101.162 +EDGE_SE3:QUAT 1945 1946 4.12195 -0.337303 -0.280472 0.000449771 0.0435039 -0.0450387 0.998037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.462 -0.15233 21.8683 399.25 0.248652 101.127 +EDGE_SE3:QUAT 1946 1947 4.06167 -0.23868 -0.11998 0.00205554 0.0445833 -0.0164218 0.998869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.6 -0.0494936 22.4627 399.204 -0.470934 101.376 +EDGE_SE3:QUAT 1947 1948 4.0425 -0.258 -0.250096 -0.00395924 0.0357221 -0.0504272 0.998081 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.621 -0.129234 17.7771 399.494 1.53985 100.635 +EDGE_SE3:QUAT 1948 1949 3.97484 -0.296761 -0.193436 -0.00787858 0.0461574 -0.0385574 0.998159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.698 -0.185521 23.0306 399.141 2.69834 101.351 +EDGE_SE3:QUAT 1949 1950 4.20071 -0.309989 -0.326205 0.00292914 0.0397001 -0.0110742 0.999146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.058 -0.0193482 19.9775 399.367 -0.789128 101.101 +EDGE_SE3:QUAT 1950 1951 3.98914 -0.377714 -0.146508 -0.00162411 0.0390004 -0.0226897 0.99898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.977 -0.0690626 19.5725 399.393 0.658975 101.017 +EDGE_SE3:QUAT 1951 1952 4.15649 -0.474466 -0.205463 0.00949467 0.0382245 -0.0750469 0.996402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.94 -0.165446 19.5456 399.394 -2.2747 100.515 +EDGE_SE3:QUAT 1952 1953 4.07392 -0.131107 -0.159059 -0.00466188 0.0408568 -0.0100466 0.999104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.164 -0.0505502 20.5172 399.327 1.473 101.169 +EDGE_SE3:QUAT 1953 1954 4.12942 -0.238501 -0.193384 -0.00677152 0.0392579 -0.0470021 0.9981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.936 -0.156131 19.4993 399.382 2.3871 100.858 +EDGE_SE3:QUAT 1954 1955 4.02161 -0.230868 -0.153143 0.000465893 0.0361841 -0.0822484 0.995955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.681 -0.191561 18.086 399.493 0.449748 100.235 +EDGE_SE3:QUAT 1955 1956 4.0127 -0.332368 -0.219003 -0.00274567 0.0420054 -0.0284021 0.99871 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.285 -0.102707 21.0692 399.296 1.05349 101.158 +EDGE_SE3:QUAT 1956 1957 4.03161 -0.142439 -0.102149 -0.00470772 0.0302214 -0.0201356 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.17 -0.0476145 15.0956 399.63 1.5295 100.603 +EDGE_SE3:QUAT 1957 1958 4.12457 -0.027463 -0.204845 -0.00233215 0.0435799 -0.0289143 0.998629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.463 -0.110099 21.8769 399.243 0.942394 101.251 +EDGE_SE3:QUAT 1958 1959 4.1822 -0.196563 -0.382705 0.00745603 0.0316021 -0.0254691 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.299 -0.0218058 15.9619 399.583 -2.07236 100.66 +EDGE_SE3:QUAT 1959 1960 4.01098 -0.16293 -0.205224 0.00248585 0.0340644 -0.0626745 0.997449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.514 -0.123195 17.135 399.541 -0.321893 100.425 +EDGE_SE3:QUAT 1960 1961 4.15577 -0.195198 -0.143934 -0.00530716 0.040586 -0.0307215 0.99869 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.11 -0.113515 20.2921 399.339 1.83014 101.064 +EDGE_SE3:QUAT 1961 1962 4.09018 -0.436098 -0.185573 0.00241587 0.0366414 -0.0428825 0.998405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.754 -0.0952677 18.4394 399.465 -0.413233 100.764 +EDGE_SE3:QUAT 1962 1963 4.23886 -0.278578 -0.0758427 -0.00544918 0.0484997 -0.0458558 0.997755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.003 -0.221807 24.2473 399.065 2.05802 101.437 +EDGE_SE3:QUAT 1963 1964 3.98134 -0.180001 -0.190638 -0.00251469 0.0492893 -0.0620656 0.996851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.115 -0.284244 24.6696 399.048 1.3454 101.311 +EDGE_SE3:QUAT 1964 1965 4.0293 -0.29605 -0.192949 -0.00814429 0.0413485 -0.0413636 0.998255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.145 -0.160854 20.5575 399.308 2.76882 101.032 +EDGE_SE3:QUAT 1965 1966 4.05788 -0.0722964 -0.149412 -0.00695352 0.0451186 -0.0433734 0.998015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.578 -0.190857 22.4941 399.185 2.45808 101.24 +EDGE_SE3:QUAT 1966 1967 4.0752 -0.299522 -0.203021 0.00430208 0.0384672 -0.0321679 0.998733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.938 -0.0692042 19.3998 399.403 -1.04309 100.948 +EDGE_SE3:QUAT 1967 1968 4.04603 -0.198135 -0.355313 -0.00170136 0.0416534 -0.0365104 0.998463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.247 -0.121838 20.8898 399.311 0.806007 101.083 +EDGE_SE3:QUAT 1968 1969 3.97505 -0.193533 -0.0404268 0.00202638 0.0424807 -0.0363226 0.998435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.359 -0.109947 21.3944 399.28 -0.303573 101.141 +EDGE_SE3:QUAT 1969 1970 3.85677 -0.19319 -0.0938565 -0.00636761 0.0419117 -0.0172705 0.998952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.26 -0.0830196 21.0111 399.288 2.04341 101.213 +EDGE_SE3:QUAT 1970 1971 3.93538 -0.192721 -0.100265 0.000160074 0.0389712 -0.0459698 0.998182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.972 -0.125514 19.5561 399.399 0.304118 100.854 +EDGE_SE3:QUAT 1971 1972 3.87697 -0.23189 -0.142868 -0.000314015 0.032459 -0.0202176 0.999269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.371 -0.039546 16.2796 399.579 0.223461 100.699 +EDGE_SE3:QUAT 1972 1973 3.93295 -0.351428 -0.0692229 0.00203878 0.0388007 -0.0322723 0.998724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.967 -0.0798561 19.5246 399.399 -0.36366 100.958 +EDGE_SE3:QUAT 1973 1974 4.08117 -0.325844 -0.143426 0.00762632 0.0383662 -0.0432627 0.998298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.934 -0.0858341 19.4504 399.394 -1.95389 100.878 +EDGE_SE3:QUAT 1974 1975 3.96931 -0.200514 -0.227838 -0.00483254 0.0421713 -0.0451678 0.998077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.267 -0.165128 21.0429 399.293 1.81689 101.04 +EDGE_SE3:QUAT 1975 1976 3.95499 -0.126193 -0.182623 0.00585735 0.0377463 -0.0208892 0.999052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.86 -0.0308111 19.0344 399.419 -1.59615 100.974 +EDGE_SE3:QUAT 1976 1977 3.93775 -0.105977 -0.299612 0.00297243 0.0373177 -0.0459606 0.998242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.822 -0.104737 18.7973 399.444 -0.551435 100.774 +EDGE_SE3:QUAT 1977 1978 3.9011 -0.365612 -0.104658 -0.00382429 0.0367298 -0.0156045 0.999196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.745 -0.0526954 18.4111 399.458 1.25608 100.926 +EDGE_SE3:QUAT 1978 1979 4.11376 -0.298042 -0.179663 1.12394e-05 0.0439115 -0.0353252 0.998411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.511 -0.123402 22.0795 399.234 0.299452 101.231 +EDGE_SE3:QUAT 1979 1980 3.83187 -0.257301 -0.171019 0.0056706 0.0455522 -0.125392 0.991045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.699 -0.448536 23.0456 399.214 -0.567606 99.8997 +EDGE_SE3:QUAT 1980 1981 3.88607 -0.285043 -0.264392 -0.000955634 0.0411783 -0.0458222 0.9981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.195 -0.14432 20.645 399.329 0.65544 100.978 +EDGE_SE3:QUAT 1981 1982 3.92373 -0.232823 -0.117316 0.00256361 0.036001 -0.0560401 0.997776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.692 -0.122264 18.1181 399.486 -0.369069 100.601 +EDGE_SE3:QUAT 1982 1983 3.89774 -0.399653 -0.203818 -0.00249614 0.0349266 -0.0713827 0.996834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.544 -0.163558 17.3477 399.525 1.2407 100.335 +EDGE_SE3:QUAT 1983 1984 3.7314 -0.326964 -0.249638 0.000917584 0.0428718 -0.0745876 0.996292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.375 -0.243285 21.5059 399.284 0.353595 100.73 +EDGE_SE3:QUAT 1984 1985 3.89 -0.181903 -0.283264 0.00154082 0.0398309 -0.0729924 0.996536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.056 -0.202943 19.9973 399.38 0.111746 100.58 +EDGE_SE3:QUAT 1985 1986 3.83248 -0.409762 -0.239389 -0.0059727 0.0370068 -0.0262899 0.998951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.748 -0.0875752 18.484 399.446 1.97715 100.896 +EDGE_SE3:QUAT 1986 1987 4.06696 -0.272481 -0.22723 0.00912487 0.048837 -0.0397976 0.997972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 403.139 -0.125804 24.8111 399.021 -2.34438 101.567 +EDGE_SE3:QUAT 1987 1988 3.94074 -0.166553 -0.203753 0.00111304 0.0478165 -0.0717279 0.996277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.962 -0.291147 24.0351 399.107 0.336801 101.089 +EDGE_SE3:QUAT 1988 1989 3.99065 -0.304642 -0.162138 -0.00401992 0.0447175 -8.52891e-05 0.998992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.607 -0.0196619 22.5156 399.195 1.20059 101.414 +EDGE_SE3:QUAT 1989 1990 3.71339 -0.218157 -0.0834343 -0.00431035 0.0299745 0.0021822 0.999539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.164 -0.00982466 15.0399 399.635 1.27724 100.636 +EDGE_SE3:QUAT 1990 1991 3.93 -0.204349 -0.129851 0.000842226 0.0355573 -0.028956 0.998948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.648 -0.0631516 17.8588 399.496 -0.049209 100.805 +EDGE_SE3:QUAT 1991 1992 3.92079 -0.288127 -0.269137 -0.00305085 0.039157 -0.0432796 0.998291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.969 -0.131575 19.569 399.392 1.24493 100.885 +EDGE_SE3:QUAT 1992 1993 3.85097 -0.408908 -0.198446 0.000392916 0.0456717 -0.0798168 0.995763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.684 -0.297973 22.8873 399.192 0.596705 100.819 +EDGE_SE3:QUAT 1993 1994 3.83342 -0.209282 -0.107311 -0.000150469 0.0381155 -0.0645708 0.997185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.873 -0.169348 19.0758 399.431 0.530056 100.597 +EDGE_SE3:QUAT 1994 1995 3.84574 -0.097062 -0.189343 -0.00316597 0.0412655 -0.0943289 0.99468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.121 -0.296207 20.4031 399.351 1.71619 100.279 +EDGE_SE3:QUAT 1995 1996 3.80267 -0.249033 -0.0632055 -0.0107645 0.0359401 -0.0452884 0.998269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.566 -0.141808 17.718 399.461 3.5411 100.713 +EDGE_SE3:QUAT 1996 1997 4.05999 -0.348409 -0.0678961 0.00223003 0.0405992 -0.0365775 0.998503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.155 -0.0999444 20.4421 399.342 -0.375396 101.029 +EDGE_SE3:QUAT 1997 1998 3.58636 -0.259717 -0.0849707 0.00115889 0.0385556 -0.0468305 0.998158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.936 -0.121384 19.3727 399.411 0.00840128 100.826 +EDGE_SE3:QUAT 1998 1999 3.75228 -0.132566 -0.0826785 0.0059232 0.040326 -0.0408794 0.998332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.135 -0.0961756 20.3952 399.341 -1.44694 100.997 +EDGE_SE3:QUAT 1999 2000 3.7061 -0.277007 -0.229495 -0.0025891 0.0340409 -0.035994 0.998769 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.492 -0.0840086 17.0125 399.539 1.01636 100.681 +EDGE_SE3:QUAT 2000 2001 3.94372 -0.364221 -0.182918 0.00452522 0.0249046 -0.0518976 0.998332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.815 -0.0473216 12.5907 399.747 -1.09897 100.177 +EDGE_SE3:QUAT 2001 2002 3.76193 -0.355789 -0.222014 -0.000598617 0.037692 -0.023899 0.999003 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.849 -0.0637852 18.9214 399.433 0.355884 100.941 +EDGE_SE3:QUAT 2002 2003 3.67902 -0.213382 -0.214829 0.00590199 0.04239 -0.0564842 0.997486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.364 -0.159349 21.4707 399.277 -1.29447 100.967 +EDGE_SE3:QUAT 2003 2004 3.91755 -0.164977 -0.10725 0.00775251 0.0321757 -0.0360504 0.998802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.353 -0.0422835 16.2965 399.567 -2.09096 100.625 +EDGE_SE3:QUAT 2004 2005 3.77653 -0.391448 -0.0360583 -0.00425336 0.0479918 -0.0215066 0.998607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.986 -0.111782 24.1231 399.077 1.469 101.577 +EDGE_SE3:QUAT 2005 2006 3.80116 -0.310168 -0.138617 0.000723133 0.0416183 -0.0403423 0.998319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.257 -0.123439 20.9225 399.312 0.11269 101.055 +EDGE_SE3:QUAT 2006 2007 3.73529 -0.459481 -0.231161 -0.00298979 0.0348349 -0.0217118 0.999153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.569 -0.0583092 17.4443 399.514 1.04323 100.805 +EDGE_SE3:QUAT 2007 2008 3.73511 -0.347834 -0.158496 -0.00360703 0.0363523 -0.0328476 0.998793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.698 -0.0915797 18.1698 399.472 1.31373 100.818 +EDGE_SE3:QUAT 2008 2009 3.80865 -0.0847682 0.0484325 -0.00227761 0.0422216 -0.0476622 0.997968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.295 -0.162957 21.1318 399.295 1.07463 101.019 +EDGE_SE3:QUAT 2009 2010 3.64592 -0.348139 -0.205187 -0.00552094 0.0369918 -0.0451154 0.998281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.73 -0.130959 18.3973 399.453 1.97987 100.753 +EDGE_SE3:QUAT 2010 2011 3.83458 -0.176115 -0.0552606 0.00558376 0.0344527 -0.0501975 0.998129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.56 -0.088923 17.4288 399.518 -1.32946 100.6 +EDGE_SE3:QUAT 2011 2012 3.76957 -0.220653 -0.136653 -0.00491237 0.0332245 -0.0190624 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.417 -0.0547152 16.6137 399.553 1.59462 100.742 +EDGE_SE3:QUAT 2012 2013 3.6968 -0.260408 -0.306459 0.0054269 0.0355806 -0.03881 0.998598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.66 -0.0694319 17.9729 399.486 -1.35126 100.755 +EDGE_SE3:QUAT 2013 2014 3.57015 -0.217549 -0.237674 0.00412865 0.0342088 -0.046709 0.998314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.534 -0.0848975 17.2578 399.529 -0.920041 100.614 +EDGE_SE3:QUAT 2014 2015 3.69388 -0.331596 -0.0171443 0.00924838 0.0268946 -0.0795643 0.996424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.963 -0.0822924 13.8482 399.686 -2.3457 99.9188 +EDGE_SE3:QUAT 2015 2016 3.75549 -0.324537 -0.270617 0.00629461 0.0378298 -0.0548355 0.997759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.884 -0.118826 19.1682 399.419 -1.4742 100.729 +EDGE_SE3:QUAT 2016 2017 3.66044 -0.416423 -0.151793 -0.00350166 0.0289592 -0.0436298 0.998622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.066 -0.0754863 14.4042 399.666 1.29912 100.395 +EDGE_SE3:QUAT 2017 2018 3.77146 -0.2592 -0.0438973 0.00683413 0.0333883 -0.0760595 0.996521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.475 -0.132786 16.9867 399.546 -1.54312 100.232 +EDGE_SE3:QUAT 2018 2019 3.69838 -0.318102 0.0969819 -0.00043888 0.0292818 -0.0452477 0.998546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.109 -0.071097 14.6455 399.661 0.394015 100.394 +EDGE_SE3:QUAT 2019 2020 3.62488 -0.229052 -0.194989 -0.00039867 0.0362915 -0.0482624 0.998175 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.705 -0.116061 18.179 399.48 0.464391 100.689 +EDGE_SE3:QUAT 2020 2021 3.67628 -0.359818 -0.0531481 0.00250998 0.0410133 -0.02576 0.998823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.2 -0.0678052 20.655 399.326 -0.543096 101.122 +EDGE_SE3:QUAT 2021 2022 3.70208 -0.00211951 0.035242 0.00502939 0.0373302 -0.0719339 0.996698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.831 -0.16386 18.8882 399.444 -0.974878 100.478 +EDGE_SE3:QUAT 2022 2023 3.70533 -0.343122 -0.21916 -0.00452807 0.0313718 -0.032247 0.998977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.254 -0.0712895 15.636 399.604 1.55531 100.587 +EDGE_SE3:QUAT 2023 2024 3.57595 -0.130087 -0.182328 -0.0023771 0.0415013 -0.0344494 0.998542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.228 -0.117439 20.803 399.315 0.990079 101.089 +EDGE_SE3:QUAT 2024 2025 3.63867 -0.362192 -0.232067 0.00202183 0.0435523 -0.0462524 0.997978 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.477 -0.150036 21.9358 399.247 -0.210142 101.124 +EDGE_SE3:QUAT 2025 2026 3.51279 -0.292839 -0.289881 -0.0152673 0.0315941 -0.0586204 0.997663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.094 -0.145738 15.2555 399.549 4.93891 100.389 +EDGE_SE3:QUAT 2026 2027 3.70234 -0.387619 -0.269292 0.00499084 0.0384739 -0.0768768 0.996286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.944 -0.188174 19.4665 399.412 -0.909677 100.465 +EDGE_SE3:QUAT 2027 2028 3.56233 -0.372679 -0.200957 -0.00218092 0.0334982 -0.0168957 0.999294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.456 -0.0418042 16.7882 399.551 0.764036 100.76 +EDGE_SE3:QUAT 2028 2029 3.49367 -0.276565 -0.111897 0.00594503 0.0346825 -0.0456022 0.99834 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.58 -0.0787813 17.5463 399.51 -1.46673 100.657 +EDGE_SE3:QUAT 2029 2030 3.55546 -0.347194 -0.147411 0.00545106 0.0404371 -0.036921 0.998485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.145 -0.0868133 20.4324 399.338 -1.33633 101.031 +EDGE_SE3:QUAT 2030 2031 3.59624 -0.121327 -0.182388 -0.00120371 0.0340008 -0.0699617 0.996969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.476 -0.148644 16.9417 399.55 0.83143 100.313 +EDGE_SE3:QUAT 2031 2032 3.67612 -0.369524 -0.125767 -0.00558404 0.0319953 -0.0665436 0.997255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.263 -0.137255 15.7639 399.595 2.09456 100.266 +EDGE_SE3:QUAT 2032 2033 3.55253 -0.266153 -0.0398371 0.00308055 0.0374781 -0.054699 0.997795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.837 -0.127646 18.8828 399.441 -0.517695 100.694 +EDGE_SE3:QUAT 2033 2034 3.58934 -0.307994 -0.207852 0.00199301 0.0337037 -0.0431244 0.998499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.483 -0.081834 16.9427 399.548 -0.309474 100.614 +EDGE_SE3:QUAT 2034 2035 3.60535 -0.133341 -0.248406 0.00730292 0.0312857 -0.0499266 0.998236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.287 -0.0660487 15.8819 399.593 -1.87718 100.465 +EDGE_SE3:QUAT 2035 2036 3.66779 -0.178988 -0.130556 1.99727e-07 0.0318102 -0.0472361 0.998377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.311 -0.0861254 15.9291 399.6 0.297183 100.485 +EDGE_SE3:QUAT 2036 2037 3.57846 -0.118432 -0.179432 0.00523429 0.0415357 -0.0501899 0.997862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.266 -0.135219 21.0064 399.306 -1.1556 100.979 +EDGE_SE3:QUAT 2037 2038 3.52523 -0.244794 -0.0520923 -0.00795802 0.031124 -0.0631883 0.997484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.167 -0.130821 15.2517 399.607 2.77361 100.277 +EDGE_SE3:QUAT 2038 2039 3.7194 -0.243581 -0.219514 0.00201916 0.0449186 -0.0589961 0.997245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.63 -0.206512 22.6194 399.204 -0.0851764 101.073 +EDGE_SE3:QUAT 2039 2040 3.43304 -0.130643 -0.142288 0.00317891 0.0341265 -0.0288442 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.523 -0.0496831 17.1758 399.532 -0.756973 100.741 +EDGE_SE3:QUAT 2040 2041 3.4791 -0.198703 -0.126062 0.00897094 0.0414268 -0.0695858 0.996675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.273 -0.181485 21.1275 399.296 -2.11555 100.77 +EDGE_SE3:QUAT 2041 2042 3.64315 -0.226554 -0.315696 0.00417214 0.0369307 -0.075846 0.996427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.787 -0.172732 18.649 399.46 -0.695191 100.394 +EDGE_SE3:QUAT 2042 2043 3.50459 -0.266466 -0.173174 -0.006712 0.0373881 -0.037498 0.998574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.765 -0.119372 18.6068 399.435 2.28286 100.842 +EDGE_SE3:QUAT 2043 2044 3.5959 -0.1959 -0.181279 -0.00582063 0.030523 -0.0416936 0.998647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.168 -0.0868727 15.1392 399.623 1.99463 100.48 +EDGE_SE3:QUAT 2044 2045 3.55489 -0.303045 -0.0642663 0.00434612 0.0361108 -0.036701 0.998664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.708 -0.0707081 18.2129 399.474 -1.03895 100.793 +EDGE_SE3:QUAT 2045 2046 3.57822 -0.142312 0.105578 0.00715571 0.0414937 -0.0654538 0.996967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.272 -0.175855 21.0769 399.303 -1.60578 100.814 +EDGE_SE3:QUAT 2046 2047 3.42728 -0.356409 -0.161725 0.00716227 0.0346202 -0.0480199 0.998221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.576 -0.0796476 17.5553 399.506 -1.81496 100.638 +EDGE_SE3:QUAT 2047 2048 3.55289 -0.156051 -0.331846 0.00481367 0.033759 -0.0363346 0.998758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.493 -0.0585026 17.0329 399.538 -1.19828 100.681 +EDGE_SE3:QUAT 2048 2049 3.55217 -0.271874 -0.0598408 0.00698311 0.0425242 -0.0450715 0.998054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.378 -0.117675 21.5501 399.264 -1.71106 101.097 +EDGE_SE3:QUAT 2049 2050 3.60147 -0.114269 0.0564121 0.000367327 0.0313306 -0.0438075 0.998549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.275 -0.0764068 15.7015 399.611 0.161562 100.496 +EDGE_SE3:QUAT 2050 2051 3.57746 -0.0468281 -0.0789584 0.000805079 0.0353065 -0.0786108 0.99628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.606 -0.17335 17.6689 399.516 0.308567 100.252 +EDGE_SE3:QUAT 2051 2052 3.63038 -0.270854 -0.0144253 -0.00329775 0.0314184 -0.0340056 0.998922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.266 -0.0707708 15.6786 399.606 1.1983 100.575 +EDGE_SE3:QUAT 2052 2053 3.31559 -0.181155 -0.304759 0.00563152 0.0387289 -0.0457096 0.998188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.97 -0.102325 19.5864 399.393 -1.33583 100.864 +EDGE_SE3:QUAT 2053 2054 3.30556 -0.217723 -0.168323 -0.00127973 0.0286396 -0.0233924 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.063 -0.0383277 14.3357 399.673 0.515802 100.52 +EDGE_SE3:QUAT 2054 2055 3.58314 -0.265036 0.0422537 0.0113658 0.0324987 -0.0288989 0.998989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.361 -0.0171657 16.4954 399.536 -3.21543 100.709 +EDGE_SE3:QUAT 2055 2056 3.48936 -0.432252 -0.0716867 -0.00444048 0.0341483 -0.0641161 0.997348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.461 -0.147455 16.9058 399.541 1.76253 100.397 +EDGE_SE3:QUAT 2056 2057 3.36455 -0.26077 -0.096088 0.00453169 0.033545 -0.0699945 0.996973 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.478 -0.128239 16.9563 399.551 -0.89185 100.313 +EDGE_SE3:QUAT 2057 2058 3.59821 -0.233977 0.0142636 -0.000533516 0.0197738 -0.0575899 0.998144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.502 -0.0413152 9.85223 399.846 0.387355 99.9402 +EDGE_SE3:QUAT 2058 2059 3.57646 -0.124742 0.00405078 -0.00227699 0.0422986 -0.0504916 0.997826 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.301 -0.172507 21.1615 399.294 1.09872 100.995 +EDGE_SE3:QUAT 2059 2060 3.42214 -0.19946 -0.141362 0.0105091 0.0365591 -0.0906975 0.995152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.787 -0.186981 18.8069 399.441 -2.48959 100.18 +EDGE_SE3:QUAT 2060 2061 3.3802 -0.21902 -0.0964095 -0.00546646 0.0316947 -0.0172651 0.999334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.286 -0.0490171 15.841 399.591 1.74393 100.681 +EDGE_SE3:QUAT 2061 2062 3.48935 -0.332609 -0.0179532 0.00392875 0.0335162 -0.0549796 0.997917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.473 -0.0989002 16.9091 399.55 -0.81168 100.496 +EDGE_SE3:QUAT 2062 2063 3.70822 -0.389152 -0.0994019 -0.00321554 0.0343602 -0.0648405 0.997299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.492 -0.147129 17.0578 399.537 1.40334 100.398 +EDGE_SE3:QUAT 2063 2064 3.39377 -0.307898 -0.0105911 0.00322322 0.0329281 -0.0832056 0.995983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.414 -0.153111 16.5852 399.575 -0.421494 100.074 +EDGE_SE3:QUAT 2064 2065 3.32351 -0.306747 -0.247074 0.00796116 0.0368915 -0.00729631 0.999261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.758 0.0129465 18.5675 399.436 -2.32719 100.973 +EDGE_SE3:QUAT 2065 2066 3.37625 -0.265736 -0.0512975 -0.00247007 0.0299585 -0.0708913 0.997031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.132 -0.120134 14.8513 399.65 1.1621 100.118 +EDGE_SE3:QUAT 2066 2067 3.34244 -0.109624 -0.375367 0.0131555 0.0351803 -0.0579461 0.997613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.628 -0.0848405 18.0749 399.451 -3.53369 100.614 +EDGE_SE3:QUAT 2067 2068 3.36437 -0.170279 -0.144049 0.000369775 0.0308414 -0.0414562 0.998664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.236 -0.0699894 15.4573 399.623 0.142289 100.495 +EDGE_SE3:QUAT 2068 2069 3.34494 -0.302038 -0.0238283 -0.00241004 0.0297188 -0.0443216 0.998572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.131 -0.0773051 14.8138 399.65 0.982635 100.419 +EDGE_SE3:QUAT 2069 2070 3.32125 -0.365839 -0.170927 -0.00386664 0.0309413 -0.0507578 0.998224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.211 -0.0984853 15.3667 399.62 1.46884 100.409 +EDGE_SE3:QUAT 2070 2071 3.34935 0.0302785 -0.221548 -0.00291595 0.0406054 -0.0340269 0.998591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.128 -0.113529 20.3375 399.343 1.14209 101.04 +EDGE_SE3:QUAT 2071 2072 3.31189 -0.293413 -0.27597 -9.22809e-05 0.0392858 -0.0317573 0.998723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.009 -0.0890787 19.7294 399.386 0.27233 100.983 +EDGE_SE3:QUAT 2072 2073 3.39301 -0.200953 -0.192076 0.000847852 0.0365338 -0.0377879 0.998617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.739 -0.0880532 18.3481 399.469 0.0181262 100.795 +EDGE_SE3:QUAT 2073 2074 3.2355 -0.281565 -0.28037 0.00505149 0.0329286 -0.0433273 0.998505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.422 -0.0684372 16.6316 399.56 -1.22996 100.588 +EDGE_SE3:QUAT 2074 2075 3.34897 -0.243918 -0.380994 0.00500255 0.0350156 -0.0401562 0.998567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.608 -0.0714876 17.6795 399.503 -1.21938 100.714 +EDGE_SE3:QUAT 2075 2076 3.09958 -0.245393 0.0389515 0.000731835 0.0366505 -0.0370715 0.99864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.749 -0.0873162 18.4051 399.466 0.0484861 100.806 +EDGE_SE3:QUAT 2076 2077 3.18686 -0.0629364 -0.322865 0.00615883 0.042348 -0.0668982 0.996842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.362 -0.192499 21.4723 399.281 -1.28498 100.839 +EDGE_SE3:QUAT 2077 2078 3.27248 -0.0802403 -0.169341 -0.000915576 0.0430879 -0.0455303 0.998033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.405 -0.156829 21.6175 399.266 0.657202 101.094 +EDGE_SE3:QUAT 2078 2079 3.36367 -0.398205 -0.153276 -0.00160061 0.0334775 -0.0442691 0.998457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.444 -0.0946215 16.7313 399.556 0.771699 100.587 +EDGE_SE3:QUAT 2079 2080 3.33689 -0.167474 -0.173329 -0.0077721 0.0344606 -0.0391602 0.998608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.48 -0.109776 17.0912 399.515 2.59161 100.684 +EDGE_SE3:QUAT 2080 2081 3.29572 -0.356409 -0.0220755 -0.00509811 0.0343676 -0.0361522 0.998742 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.501 -0.0942954 17.1216 399.525 1.77033 100.698 +EDGE_SE3:QUAT 2081 2082 3.10932 -0.101866 -0.187508 0.00436475 0.029156 -0.0523151 0.998195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.116 -0.0680686 14.7234 399.656 -1.00474 100.334 +EDGE_SE3:QUAT 2082 2083 3.385 -0.228971 0.0418952 0.00115797 0.0275264 -0.0501033 0.998364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.985 -0.0653241 13.8034 399.7 -0.0730765 100.281 +EDGE_SE3:QUAT 2083 2084 3.1837 -0.327535 -0.147419 0.00158241 0.0342924 -0.0366521 0.998738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.534 -0.0724418 17.2312 399.531 -0.225577 100.693 +EDGE_SE3:QUAT 2084 2085 3.33913 -0.3002 -0.0953406 0.0043408 0.0320394 -0.0444748 0.998487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.346 -0.0687878 16.1656 399.585 -1.01759 100.534 +EDGE_SE3:QUAT 2085 2086 3.29366 -0.112846 -0.182767 0.00376743 0.0423855 -0.0733684 0.996397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 402.349 -0.223351 21.3905 399.292 -0.515536 100.734 +EDGE_SE3:QUAT 2086 2087 3.26502 -0.225465 -0.133874 -0.0020519 0.0357826 -0.0792797 0.996208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.619 -0.187693 17.7691 399.505 1.17603 100.256 +EDGE_SE3:QUAT 2087 2088 3.31718 -0.467704 -0.249224 0.00613332 0.0340062 -0.0819932 0.996034 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.527 -0.152973 17.2729 399.535 -1.28386 100.163 +EDGE_SE3:QUAT 2088 2089 3.36706 -0.255742 -0.186457 -0.0094464 0.0329107 -0.0320866 0.998898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.336 -0.0932208 16.3164 399.546 3.03526 100.671 +EDGE_SE3:QUAT 2089 2090 3.29221 -0.213925 -0.221204 -0.00291805 0.0318528 -0.0698691 0.997043 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.278 -0.134888 15.7879 399.604 1.31554 100.213 +EDGE_SE3:QUAT 2090 2091 3.14634 -0.287549 -0.0415104 -0.00360592 0.0240009 -0.0415704 0.998841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.728 -0.0512288 11.9151 399.769 1.27898 100.23 +EDGE_SE3:QUAT 2091 2092 3.4355 -0.164266 -0.241845 -0.00199667 0.0337293 -0.0404398 0.998611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.465 -0.0895737 16.8574 399.549 0.866709 100.632 +EDGE_SE3:QUAT 2092 2093 3.15122 -0.262831 -0.209649 0.00124638 0.0220243 -0.0835987 0.996255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.627 -0.0702772 11.0239 399.811 -0.00539548 99.6404 +EDGE_SE3:QUAT 2093 2094 3.23982 -0.0802858 0.00519565 0.00255444 0.034435 -0.074422 0.996629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.544 -0.150958 17.3174 399.534 -0.257331 100.281 +EDGE_SE3:QUAT 2094 2095 3.41168 -0.298765 -0.0959007 0.0022574 0.0357628 -0.0415318 0.998494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.671 -0.0879625 17.9905 399.49 -0.382642 100.73 +EDGE_SE3:QUAT 2095 2096 3.19036 -0.336984 -0.0754017 0.00323176 0.0367309 -0.0532594 0.9979 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.765 -0.118315 18.5096 399.462 -0.581267 100.671 +EDGE_SE3:QUAT 2096 2097 2.9825 -0.240019 -0.230277 -0.00283622 0.0334267 -0.0535781 0.998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.424 -0.116502 16.6422 399.559 1.20303 100.49 +EDGE_SE3:QUAT 2097 2098 3.24548 -0.418819 -0.0919402 -0.0062192 0.0280012 -0.0125334 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.998 -0.0354686 13.9893 399.676 1.93161 100.543 +EDGE_SE3:QUAT 2098 2099 3.16442 -0.257845 -0.351951 0.000627216 0.0143432 -0.0785297 0.996808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.265 -0.0281274 7.16642 399.92 0.0378043 99.5269 +EDGE_SE3:QUAT 2099 2100 3.13503 -0.170765 -0.0585885 -0.00101249 0.0341397 -0.0562743 0.997831 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.499 -0.121242 17.0553 399.542 0.682714 100.496 +EDGE_SE3:QUAT 2100 2101 3.11874 -0.201613 -0.165434 0.00640456 0.0364336 -0.0765934 0.996376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.752 -0.162753 18.5023 399.465 -1.36526 100.371 +EDGE_SE3:QUAT 2101 2102 3.21948 -0.242775 -0.154584 -0.00248509 0.0358006 -0.0789086 0.996236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.616 -0.188268 17.7587 399.504 1.30334 100.262 +EDGE_SE3:QUAT 2102 2103 3.08549 -0.199584 -0.183659 -0.0024582 0.0323223 -0.0646696 0.99738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.325 -0.128211 16.0617 399.591 1.15033 100.306 +EDGE_SE3:QUAT 2103 2104 3.24132 -0.241215 -0.292536 0.00301133 0.0289867 -0.0697871 0.997136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.098 -0.0976972 14.599 399.667 -0.500144 100.108 +EDGE_SE3:QUAT 2104 2105 3.12134 -0.301012 -0.098041 0.0074401 0.0287504 -0.0435098 0.998612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.083 -0.0438536 14.5878 399.652 -1.98008 100.417 +EDGE_SE3:QUAT 2105 2106 3.19036 -0.30163 -0.207732 0.00151718 0.0352351 -0.0581445 0.997685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.615 -0.125072 17.6934 399.51 -0.0495018 100.534 +EDGE_SE3:QUAT 2106 2107 3.11121 -0.241309 0.0191096 -0.00705286 0.0301883 -0.061125 0.997649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.109 -0.118277 14.8285 399.632 2.47876 100.261 +EDGE_SE3:QUAT 2107 2108 3.07783 -0.278546 -0.123676 -0.000958253 0.0308498 -0.104157 0.994082 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.192 -0.177834 15.263 399.641 0.929292 99.5677 +EDGE_SE3:QUAT 2108 2109 3.16526 -0.0937671 -0.16787 0.00085598 0.0357482 -0.0550345 0.997844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.659 -0.123876 17.9333 399.496 0.132022 100.593 +EDGE_SE3:QUAT 2109 2110 3.00497 -0.303564 -0.00339931 0.00182294 0.0314129 -0.0618389 0.99759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.284 -0.104556 15.7744 399.61 -0.160892 100.311 +EDGE_SE3:QUAT 2110 2111 3.15378 -0.297936 -0.0224724 0.000189194 0.0278363 -0.0436926 0.998657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.005 -0.0604677 13.9368 399.693 0.184599 100.351 +EDGE_SE3:QUAT 2111 2112 3.16663 -0.0369884 -0.0054611 -0.00438555 0.027783 -0.0354622 0.998975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.979 -0.0611276 13.8186 399.689 1.50877 100.415 +EDGE_SE3:QUAT 2112 2113 3.0169 -0.117958 -0.0508984 -0.00220296 0.037046 -0.0663459 0.997106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.748 -0.170824 18.4478 399.464 1.14427 100.513 +EDGE_SE3:QUAT 2113 2114 3.18669 -0.224334 -0.153768 0.00332575 0.0314784 -0.0265936 0.999145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.295 -0.0369677 15.8374 399.601 -0.829978 100.631 +EDGE_SE3:QUAT 2114 2115 2.91763 -0.188078 -0.206345 0.00117583 0.0361007 -0.0418156 0.998472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.698 -0.0942389 18.134 399.482 -0.0543952 100.741 +EDGE_SE3:QUAT 2115 2116 3.14354 0.00118941 -0.1014 0.000796421 0.0353351 -0.0692795 0.996971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.614 -0.152971 17.7007 399.512 0.245656 100.393 +EDGE_SE3:QUAT 2116 2117 2.96317 -0.239017 -0.116822 0.00858454 0.0354262 -0.0490474 0.998131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.651 -0.0813374 18.008 399.476 -2.22554 100.678 +EDGE_SE3:QUAT 2117 2118 3.13744 -0.0938027 0.103234 0.013088 0.028408 -0.0464844 0.998429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.039 -0.0308121 14.5832 399.622 -3.65748 100.421 +EDGE_SE3:QUAT 2118 2119 3.08753 -0.21266 0.050822 -0.000510603 0.0321189 -0.0289387 0.999065 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.34 -0.0555676 16.0963 399.589 0.336363 100.639 +EDGE_SE3:QUAT 2119 2120 2.90142 -0.20835 -0.214941 -0.00637702 0.0281956 -0.0513365 0.998263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.979 -0.0895993 13.9042 399.678 2.1976 100.293 +EDGE_SE3:QUAT 2120 2121 2.94659 -0.185591 -0.298557 -0.0017594 0.0216076 -0.0402213 0.998956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.598 -0.037383 10.7629 399.814 0.70041 100.164 +EDGE_SE3:QUAT 2121 2122 3.05456 -0.147706 -0.163355 0.00549841 0.0218517 -0.0466757 0.998656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.626 -0.0285972 11.0772 399.8 -1.44496 100.132 +EDGE_SE3:QUAT 2122 2123 2.86447 -0.186523 -0.103665 0.0036815 0.0206054 -0.0547156 0.998283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.558 -0.0347499 10.4114 399.827 -0.878916 100.006 +EDGE_SE3:QUAT 2123 2124 3.04689 -0.297491 -0.102629 0.00478112 0.0299774 -0.0855996 0.995867 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.182 -0.126401 15.1835 399.642 -0.921977 99.912 +EDGE_SE3:QUAT 2124 2125 3.08765 -0.250439 -0.0506802 0.00841303 0.0192357 -0.0675454 0.997495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.487 -0.0303399 9.93232 399.83 -2.26358 99.8356 +EDGE_SE3:QUAT 2125 2126 3.02846 -0.27499 -0.229663 -0.00188242 0.0249224 -0.0076312 0.999658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.806 -0.0133413 12.479 399.751 0.601583 100.43 +EDGE_SE3:QUAT 2126 2127 2.94135 -0.331537 -0.163876 3.49104e-05 0.0359433 -0.0265914 0.999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.682 -0.0620076 18.0421 399.485 0.177628 100.837 +EDGE_SE3:QUAT 2127 2128 2.99822 -0.316052 -0.0903634 0.00507244 0.0234134 -0.0177058 0.999556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.71 -0.00543799 11.7799 399.773 -1.43735 100.363 +EDGE_SE3:QUAT 2128 2129 3.09378 -0.059808 -0.0984537 -0.00626081 0.0363102 -0.0884774 0.995396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.595 -0.224558 17.7701 399.489 2.51201 100.119 +EDGE_SE3:QUAT 2129 2130 3.06748 -0.19482 -0.204036 0.00220475 0.0274665 -0.0404444 0.998802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.985 -0.0490955 13.8031 399.698 -0.44001 100.369 +EDGE_SE3:QUAT 2130 2131 2.88483 -0.267356 -0.0967774 -0.0069175 0.036608 -0.0377988 0.998591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.688 -0.116286 18.2054 399.457 2.34124 100.8 +EDGE_SE3:QUAT 2131 2132 3.02909 -0.170109 -0.18227 0.00407651 0.0320597 -0.0810115 0.996189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.347 -0.138595 16.1918 399.593 -0.705324 100.075 +EDGE_SE3:QUAT 2132 2133 2.86662 -0.358957 -0.152816 -0.00797923 0.0277493 -0.0458357 0.998532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.935 -0.0838473 13.663 399.68 2.64255 100.335 +EDGE_SE3:QUAT 2133 2134 3.03495 -0.282425 0.129501 0.00249171 0.0164194 -0.0642051 0.997799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.354 -0.0274517 8.28305 399.891 -0.536556 99.7803 +EDGE_SE3:QUAT 2134 2135 3.03235 -0.337068 -0.0352917 0.0016509 0.0319909 -0.0262853 0.999141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.336 -0.0432413 16.0692 399.591 -0.328009 100.651 +EDGE_SE3:QUAT 2135 2136 2.99134 -0.374864 -0.0640829 0.00284413 0.0284179 -0.10373 0.994195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.048 -0.143708 14.2881 399.689 -0.263346 99.4929 +EDGE_SE3:QUAT 2136 2137 2.85107 -0.177509 0.0270334 -0.000887442 0.027188 -0.0439967 0.998661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.954 -0.0608405 13.5816 399.707 0.503245 100.322 +EDGE_SE3:QUAT 2137 2138 2.705 -0.398588 -0.0867881 0.00498078 0.0260821 -0.0456778 0.998603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.892 -0.0434499 13.1849 399.721 -1.25554 100.282 +EDGE_SE3:QUAT 2138 2139 3.02087 -0.144757 -0.00298317 -0.00949895 0.037348 -0.0510771 0.997951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.705 -0.161128 18.4224 399.43 3.21703 100.721 +EDGE_SE3:QUAT 2139 2140 3.01131 -0.236663 -0.092828 -0.0029631 0.0263875 -0.0847738 0.996046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.862 -0.110984 12.9877 399.731 1.33524 99.7586 +EDGE_SE3:QUAT 2140 2141 2.85416 -0.214898 -0.0965311 -0.00575467 0.034684 -0.0910326 0.995227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.455 -0.209159 16.964 399.536 2.35129 99.9931 +EDGE_SE3:QUAT 2141 2142 2.96134 -0.228075 -0.0354297 -0.00287482 0.0229425 -0.0459246 0.998677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.667 -0.0495594 11.3906 399.79 1.07139 100.156 +EDGE_SE3:QUAT 2142 2143 2.93735 -0.211107 -0.0533829 -0.00632507 0.0293669 -0.0517518 0.998208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.065 -0.0970543 14.4928 399.651 2.19585 100.335 +EDGE_SE3:QUAT 2143 2144 2.94033 -0.239342 -0.134921 0.00350488 0.0265997 -0.0626584 0.997674 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.928 -0.0712955 13.4181 399.717 -0.718741 100.111 +EDGE_SE3:QUAT 2144 2145 2.82771 -0.058074 -0.0847544 -0.000228715 0.0386366 -0.049231 0.99804 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.934 -0.133521 19.3695 399.41 0.442359 100.803 +EDGE_SE3:QUAT 2145 2146 2.81758 -0.241485 -0.0455579 -0.00137085 0.038541 -0.0407329 0.998426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.921 -0.114573 19.3074 399.411 0.718292 100.874 +EDGE_SE3:QUAT 2146 2147 2.74998 -0.415505 0.0589001 -0.00566004 0.0203644 -0.0600774 0.99797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.497 -0.0543281 9.95839 399.83 1.94165 99.9294 +EDGE_SE3:QUAT 2147 2148 2.83017 -0.13845 -0.0723086 -0.00127019 0.0311129 -0.0608058 0.997664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.24 -0.109275 15.5097 399.62 0.755456 100.303 +EDGE_SE3:QUAT 2148 2149 2.8416 -0.184699 -0.0206475 0.0037625 0.030614 -0.0675782 0.997237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.229 -0.103647 15.4477 399.626 -0.716401 100.21 +EDGE_SE3:QUAT 2149 2150 2.76972 0.0193745 -0.116096 0.000518068 0.0302759 -0.0738681 0.996808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.181 -0.120031 15.1344 399.643 0.289229 100.093 +EDGE_SE3:QUAT 2150 2151 2.79106 -0.395836 -0.144435 0.00821879 0.0247667 -0.0802203 0.996436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.817 -0.0712583 12.7351 399.736 -2.06771 99.8221 +EDGE_SE3:QUAT 2151 2152 3.00288 -0.14102 0.0517604 0.00384665 0.0312283 -0.0372551 0.99881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.277 -0.0536428 15.7347 399.606 -0.921396 100.554 +EDGE_SE3:QUAT 2152 2153 2.80302 -0.297836 -0.17321 -0.00417417 0.0176588 -0.0698241 0.997394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.375 -0.0447254 8.62461 399.875 1.49919 99.7283 +EDGE_SE3:QUAT 2153 2154 2.90242 -0.325618 -0.140133 0.00171906 0.0270875 -0.0518416 0.998286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.956 -0.0640879 13.5994 399.709 -0.236087 100.248 +EDGE_SE3:QUAT 2154 2155 2.82276 -0.191489 -0.172371 -0.00373928 0.0294013 -0.0391579 0.998793 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.1 -0.0715806 14.6355 399.654 1.34773 100.451 +EDGE_SE3:QUAT 2155 2156 2.67414 -0.152866 -0.173903 -0.00744681 0.0213961 -0.0867212 0.995975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.513 -0.0812485 10.2528 399.812 2.60633 99.5653 +EDGE_SE3:QUAT 2156 2157 2.82588 -0.271739 -0.046187 0.00109296 0.0263197 -0.0464949 0.998571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.901 -0.0552435 13.1967 399.725 -0.0843733 100.27 +EDGE_SE3:QUAT 2157 2158 2.74048 -0.220883 -0.228373 0.00554675 0.0265052 -0.0384593 0.998893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.919 -0.0342113 13.3963 399.71 -1.45917 100.36 +EDGE_SE3:QUAT 2158 2159 2.63973 -0.0802336 -0.190278 -0.00190545 0.0278607 -0.0738741 0.996877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.98 -0.10692 13.8136 399.698 0.980915 99.9903 +EDGE_SE3:QUAT 2159 2160 2.76106 -0.346252 -0.116985 -0.0101271 0.0144914 -0.0180566 0.999681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.222 -0.0210513 7.13818 399.886 3.08881 100.142 +EDGE_SE3:QUAT 2160 2161 2.62533 -0.340821 -0.0992983 -0.00624034 0.0312397 -0.0369289 0.99881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.226 -0.0838579 15.5131 399.604 2.09617 100.55 +EDGE_SE3:QUAT 2161 2162 2.6436 -0.257744 -0.0761311 0.0012484 0.0322143 -0.0693646 0.99707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.344 -0.125757 16.1475 399.593 0.0691837 100.246 +EDGE_SE3:QUAT 2162 2163 2.77023 -0.410161 -0.124668 -0.00637815 0.0313138 -0.0644433 0.99741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.201 -0.130319 15.401 399.609 2.31058 100.265 +EDGE_SE3:QUAT 2163 2164 2.58488 -0.278603 0.0174039 -0.00293729 0.0277734 -0.0608267 0.997758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.973 -0.0913237 13.769 399.697 1.21589 100.165 +EDGE_SE3:QUAT 2164 2165 2.60739 -0.257122 -0.101955 -0.00605267 0.0336918 -0.0479975 0.998261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.421 -0.117215 16.6998 399.544 2.13095 100.563 +EDGE_SE3:QUAT 2165 2166 2.68056 -0.273622 0.0528448 0.00228341 0.0228523 -0.0549787 0.998223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.682 -0.046806 11.4915 399.792 -0.434154 100.067 +EDGE_SE3:QUAT 2166 2167 2.81107 -0.156203 0.0491687 -0.00606799 0.0309053 -0.0187825 0.999327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.216 -0.0514349 15.4296 399.609 1.93084 100.642 +EDGE_SE3:QUAT 2167 2168 2.76063 -0.105588 0.0212139 -0.000165912 0.0219773 -0.066513 0.997543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.62 -0.0578482 10.9565 399.811 0.341587 99.8934 +EDGE_SE3:QUAT 2168 2169 2.60847 -0.34208 -0.191335 0.00763177 0.0281257 -0.0520849 0.998217 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.04 -0.0537196 14.3074 399.666 -1.99521 100.312 +EDGE_SE3:QUAT 2169 2170 2.69378 -0.243534 0.0365211 0.00482026 0.0239272 -0.0695123 0.997282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.755 -0.0613932 12.1373 399.766 -1.11342 99.9317 +EDGE_SE3:QUAT 2170 2171 2.56223 -0.091304 0.0936846 0.00265445 0.018079 -0.0638566 0.997792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.429 -0.033214 9.11849 399.869 -0.565378 99.8255 +EDGE_SE3:QUAT 2171 2172 2.62996 -0.251588 -0.126104 0.00491618 0.0265796 -0.0512465 0.99832 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.928 -0.0528127 13.4433 399.711 -1.20226 100.246 +EDGE_SE3:QUAT 2172 2173 2.57139 -0.170799 -0.0875925 -0.00321743 0.029739 -0.066912 0.99731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.111 -0.114203 14.724 399.654 1.35919 100.164 +EDGE_SE3:QUAT 2173 2174 2.78383 -0.163845 -0.171656 0.00308902 0.0237284 -0.0590254 0.99797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.738 -0.0530638 11.9601 399.774 -0.646915 100.052 +EDGE_SE3:QUAT 2174 2175 2.56906 -0.20738 -0.138053 -0.00533415 0.0331988 -0.052738 0.998042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.381 -0.120828 16.4495 399.56 1.94292 100.49 +EDGE_SE3:QUAT 2175 2176 2.58835 -0.1435 -0.203424 -0.00949419 0.0282012 -0.0538584 0.998105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.94 -0.100473 13.7915 399.665 3.14579 100.275 +EDGE_SE3:QUAT 2176 2177 2.78201 -0.0757288 -0.0590521 0.000524765 0.0303596 -0.0660433 0.997355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.19 -0.107888 15.1894 399.639 0.240795 100.208 +EDGE_SE3:QUAT 2177 2178 2.71021 -0.280013 -0.0592529 -0.00717533 0.0220772 -0.0295779 0.999293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.595 -0.0412338 10.92 399.792 2.2802 100.264 +EDGE_SE3:QUAT 2178 2179 2.55366 -0.245601 -0.0176089 0.00522138 0.0316 -0.0151914 0.999372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.299 -0.0103591 15.8999 399.592 -1.46773 100.689 +EDGE_SE3:QUAT 2179 2180 2.5375 -0.322054 -0.168304 -0.00736017 0.0338001 -0.0868458 0.995621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.36 -0.194792 16.4613 399.552 2.78824 100.029 +EDGE_SE3:QUAT 2180 2181 2.63204 -0.139707 -0.0836986 -0.000457223 0.0227816 -0.0542143 0.998269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.668 -0.0514647 11.3662 399.796 0.383151 100.068 +EDGE_SE3:QUAT 2181 2182 2.60929 -0.226707 -0.0366647 -0.00251156 0.0255909 -0.0607925 0.997819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.828 -0.0770053 12.6894 399.743 1.06244 100.084 +EDGE_SE3:QUAT 2182 2183 2.46535 -0.163446 -0.0820948 -0.00621354 0.0348425 -0.0552649 0.997844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.511 -0.140361 17.2366 399.515 2.23987 100.541 +EDGE_SE3:QUAT 2183 2184 2.60707 -0.173847 0.0184197 -0.00297004 0.0249163 -0.0840742 0.996144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.767 -0.0984816 12.2543 399.76 1.30943 99.7186 +EDGE_SE3:QUAT 2184 2185 2.63386 -0.098519 0.0738556 -0.00201271 0.0290361 -0.0760685 0.996678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.063 -0.119415 14.3915 399.673 1.04275 100.003 +EDGE_SE3:QUAT 2185 2186 2.58423 -0.145607 -0.0829623 -0.0102815 0.0328145 -0.0416388 0.998541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.304 -0.11269 16.1809 399.547 3.34719 100.596 +EDGE_SE3:QUAT 2186 2187 2.71082 -0.231633 -0.0952657 0.00436599 0.020124 -0.0739362 0.99705 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.535 -0.0462462 10.2207 399.834 -1.01203 99.7481 +EDGE_SE3:QUAT 2187 2188 2.66462 -0.138512 0.0944016 -1.04468e-05 0.0217383 -0.0408704 0.998928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.612 -0.0347679 10.8704 399.813 0.180031 100.163 +EDGE_SE3:QUAT 2188 2189 2.40702 -0.191167 -0.0507019 0.00221469 0.0226982 -0.0411488 0.998893 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.673 -0.033322 11.4071 399.793 -0.477878 100.195 +EDGE_SE3:QUAT 2189 2190 2.58494 -0.380584 -0.098209 0.00930013 0.023393 -0.0675538 0.997398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.722 -0.0468328 12.049 399.754 -2.47295 99.9683 +EDGE_SE3:QUAT 2190 2191 2.56239 -0.261385 -0.0668467 0.00564617 0.0239724 -0.0496573 0.998463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.755 -0.0384864 12.1527 399.761 -1.4552 100.172 +EDGE_SE3:QUAT 2191 2192 2.51927 -0.168366 -0.131046 0.00891981 0.0266411 -0.0474574 0.998478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.928 -0.0375814 13.5819 399.691 -2.42095 100.308 +EDGE_SE3:QUAT 2192 2193 2.53748 -0.046566 -0.0662339 0.00670164 0.0306846 -0.0698987 0.99706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.245 -0.100147 15.6084 399.613 -1.58163 100.198 +EDGE_SE3:QUAT 2193 2194 2.46796 -0.0634905 0.0617769 0.000129471 0.0256417 -0.0701938 0.997204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.845 -0.0823885 12.7984 399.743 0.319897 99.965 +EDGE_SE3:QUAT 2194 2195 2.55324 -0.21086 -0.0280942 0.00495726 0.0247729 -0.0506795 0.998395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.806 -0.0443565 12.5359 399.748 -1.23579 100.187 +EDGE_SE3:QUAT 2195 2196 2.49325 -0.160726 -0.0387394 0.00611079 0.024 -0.0171859 0.999546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.744 -0.00291148 12.0841 399.758 -1.74873 100.388 +EDGE_SE3:QUAT 2196 2197 2.74131 -0.235165 -0.181812 -0.00702188 0.022565 -0.074773 0.996921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.591 -0.0799533 10.9282 399.792 2.44324 99.7953 +EDGE_SE3:QUAT 2197 2198 2.54727 -0.175575 -0.0673235 0.00573996 0.0279191 -0.0212584 0.999368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.013 -0.0135564 14.0656 399.678 -1.60115 100.515 +EDGE_SE3:QUAT 2198 2199 2.443 -0.192448 -0.197352 0.0015658 0.0157361 -0.0556297 0.998326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.323 -0.0224909 7.90523 399.901 -0.294637 99.8655 +EDGE_SE3:QUAT 2199 2200 2.55334 -0.114688 0.105397 0.00291777 0.0206665 -0.0687851 0.997413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.56 -0.0474806 10.4253 399.829 -0.591022 99.8314 +EDGE_SE3:QUAT 2200 2201 2.53868 -0.156379 0.025403 0.00183456 0.0227783 -0.0579331 0.998059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.677 -0.050204 11.4393 399.794 -0.286942 100.03 +EDGE_SE3:QUAT 2201 2202 2.31722 -0.198021 -0.104894 0.000431477 0.0293278 -0.0518219 0.998226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.115 -0.079029 14.6858 399.66 0.172165 100.333 +EDGE_SE3:QUAT 2202 2203 2.3647 -0.198329 -0.124762 0.0128042 0.0233249 -0.0549062 0.998137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.697 -0.0249636 12.0759 399.73 -3.5824 100.147 +EDGE_SE3:QUAT 2203 2204 2.56192 -0.239004 -0.0748405 0.0055313 0.030162 -0.0553735 0.997995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.197 -0.0750579 15.2725 399.629 -1.32537 100.349 +EDGE_SE3:QUAT 2204 2205 2.48643 -0.155395 -0.0622614 -0.00534271 0.0246847 -0.0770622 0.996706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.733 -0.0938684 12.0531 399.759 1.98194 99.8257 +EDGE_SE3:QUAT 2205 2206 2.53363 -0.216545 -0.147638 -0.00468862 0.0240468 -0.0361257 0.999047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.727 -0.0483887 11.9309 399.765 1.57757 100.276 +EDGE_SE3:QUAT 2206 2207 2.42826 -0.25274 -0.116226 -0.003539 0.0334616 -0.0708614 0.996918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.405 -0.15215 16.5667 399.563 1.52962 100.271 +EDGE_SE3:QUAT 2207 2208 2.32818 -0.142037 0.145586 0.00503573 0.0240505 -0.0381585 0.99897 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.757 -0.0278751 12.1497 399.761 -1.32645 100.272 +EDGE_SE3:QUAT 2208 2209 2.30257 -0.272176 -0.102851 -0.00428192 0.0218428 -0.0491103 0.998545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.593 -0.0505385 10.7887 399.808 1.49736 100.092 +EDGE_SE3:QUAT 2209 2210 2.45692 -0.193683 0.00993662 0.00522671 0.0183147 -0.0266376 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.434 -0.00651962 9.24591 399.857 -1.46964 100.175 +EDGE_SE3:QUAT 2210 2211 2.51071 -0.198808 -0.0302144 0.00166825 0.0301684 -0.0155202 0.999423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.187 -0.0203553 15.1448 399.635 -0.406794 100.617 +EDGE_SE3:QUAT 2211 2212 2.49369 -0.0733512 -0.0799538 0.000182349 0.0189128 -0.0512674 0.998506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.463 -0.0326091 9.45136 399.859 0.138854 99.9869 +EDGE_SE3:QUAT 2212 2213 2.39006 -0.153298 0.0373865 -0.0102642 0.0264001 -0.0397655 0.998807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.823 -0.0751353 12.9648 399.696 3.28323 100.348 +EDGE_SE3:QUAT 2213 2214 2.43932 -0.0730176 -0.088475 -0.00171632 0.0256153 -0.0525917 0.998286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.838 -0.0660091 12.7502 399.741 0.782214 100.18 +EDGE_SE3:QUAT 2214 2215 2.18211 -0.134376 -0.15483 -0.00360307 0.020786 -0.0650066 0.997662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.533 -0.0564888 10.2276 399.829 1.35048 99.8762 +EDGE_SE3:QUAT 2215 2216 2.41499 -0.0178778 0.040534 -0.00918297 0.0332127 -0.0370672 0.998718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.358 -0.103219 16.441 399.541 2.9911 100.647 +EDGE_SE3:QUAT 2216 2217 2.23393 -0.421369 -0.0605318 -0.00475852 0.0233356 -0.0582906 0.998016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.67 -0.0665184 11.4863 399.782 1.6976 100.039 +EDGE_SE3:QUAT 2217 2218 2.28824 -0.187991 0.266978 -0.00352657 0.0227429 -0.0617166 0.997828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.644 -0.0640419 11.2212 399.795 1.33728 99.9773 +EDGE_SE3:QUAT 2218 2219 2.21914 -0.0891997 0.0758099 -0.00132931 0.0311132 -0.0250294 0.999202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.255 -0.0479378 15.5803 399.614 0.551757 100.616 +EDGE_SE3:QUAT 2219 2220 2.28897 -0.277102 -0.0897139 0.00343559 0.0161498 -0.0313866 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.34 -0.00927028 8.13991 399.892 -0.929033 100.09 +EDGE_SE3:QUAT 2220 2221 2.40356 -0.0794056 -0.0707853 0.0049322 0.0212876 -0.03736 0.999063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.592 -0.0201925 10.7582 399.811 -1.31996 100.189 +EDGE_SE3:QUAT 2221 2222 2.41028 -0.240465 -0.00656688 -0.00475964 0.0217886 -0.103476 0.994382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.553 -0.0927927 10.5101 399.817 1.88204 99.2503 +EDGE_SE3:QUAT 2222 2223 2.21486 -0.265447 -0.108695 -0.00299028 0.021 -0.0538291 0.998325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.554 -0.0481747 10.3915 399.825 1.12203 100.017 +EDGE_SE3:QUAT 2223 2224 2.35291 -0.0587143 0.16297 -0.00394518 0.0127652 -0.0480489 0.998756 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.196 -0.0185058 6.25895 399.932 1.30624 99.8846 +EDGE_SE3:QUAT 2224 2225 2.49824 -0.381568 -0.247656 0.0100056 0.0248707 -0.0326931 0.999106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.792 -0.0113679 12.6471 399.721 -2.83585 100.366 +EDGE_SE3:QUAT 2225 2226 2.38142 -0.166439 -0.211008 0.00300444 0.022328 -0.0531247 0.998334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.653 -0.0413928 11.2512 399.799 -0.664278 100.073 +EDGE_SE3:QUAT 2226 2227 2.27315 -0.201948 0.145509 0.00936833 0.0217535 -0.0561936 0.998139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.617 -0.0285742 11.1805 399.783 -2.56473 100.054 +EDGE_SE3:QUAT 2227 2228 2.13866 -0.323873 0.0584076 0.00412569 0.0249486 -0.0394003 0.998903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.815 -0.0341274 12.5821 399.746 -1.04079 100.29 +EDGE_SE3:QUAT 2228 2229 2.24573 -0.226832 -0.0876004 -0.000261252 0.0208576 -0.0416956 0.998913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.563 -0.0331396 10.4217 399.828 0.251571 100.13 +EDGE_SE3:QUAT 2229 2230 2.14541 -0.0988302 -0.00688579 0.0014205 0.0219946 -0.0607915 0.997907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.629 -0.0499941 11.0312 399.809 -0.159178 99.9704 +EDGE_SE3:QUAT 2230 2231 2.26833 -0.119201 -0.16057 -0.00065946 0.0339447 -0.0192989 0.999237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.499 -0.0425171 17.0275 399.54 0.326377 100.772 +EDGE_SE3:QUAT 2231 2232 2.20321 -0.234994 -0.0591747 -0.00233208 0.0318573 -0.0433764 0.998548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.302 -0.0864706 15.8963 399.598 0.971363 100.52 +EDGE_SE3:QUAT 2232 2233 2.30716 -0.30245 -0.0345714 0.00312462 0.0321733 -0.0442513 0.998497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.354 -0.0728374 16.2003 399.585 -0.653821 100.537 +EDGE_SE3:QUAT 2233 2234 2.34224 -0.0479596 -0.117307 0.0101756 0.0227121 -0.072471 0.99706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.681 -0.046703 11.7665 399.761 -2.72251 99.8848 +EDGE_SE3:QUAT 2234 2235 2.10604 -0.211645 -0.0377961 -0.000569033 0.0131514 -0.0536998 0.99847 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.222 -0.0173174 6.54422 399.932 0.312059 99.8318 +EDGE_SE3:QUAT 2235 2236 2.18674 -0.387761 -0.0670731 -0.010534 0.0253996 -0.0688573 0.997247 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.719 -0.100373 12.234 399.722 3.50656 99.9863 +EDGE_SE3:QUAT 2236 2237 2.29351 -0.21551 -0.127336 -0.00407112 0.0238296 -0.0262172 0.999364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.722 -0.0363899 11.8663 399.77 1.34387 100.331 +EDGE_SE3:QUAT 2237 2238 2.21828 -0.0361587 -0.149308 0.00252351 0.0260096 -0.0688479 0.997285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.883 -0.0778835 13.0846 399.732 -0.399705 100.004 +EDGE_SE3:QUAT 2238 2239 2.13603 -0.438616 0.185176 -0.00321807 0.0202727 -0.0958564 0.995184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.495 -0.0740461 9.88093 399.842 1.35623 99.3605 +EDGE_SE3:QUAT 2239 2240 2.14175 -0.0934289 -0.0927082 -0.00473226 0.0150485 -0.069516 0.997456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.264 -0.0336527 7.29955 399.907 1.6297 99.675 +EDGE_SE3:QUAT 2240 2241 2.27455 -0.0841658 -0.153554 -0.00135294 0.025339 -0.0670775 0.997425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.817 -0.0800553 12.5913 399.749 0.744235 99.9948 +EDGE_SE3:QUAT 2241 2242 2.40569 -0.0856973 0.00508491 -0.00137053 0.013716 -0.0596172 0.998126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.238 -0.0216945 6.79142 399.926 0.574946 99.7748 +EDGE_SE3:QUAT 2242 2243 2.19892 -0.305506 -0.00208666 0.0009404 0.0189473 -0.0772889 0.996828 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.464 -0.0481509 9.47807 399.86 0.0111239 99.6536 +EDGE_SE3:QUAT 2243 2244 2.10773 -0.261746 -0.20281 -0.00119969 0.0211096 -0.0471762 0.998663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.572 -0.0401173 10.5158 399.824 0.55812 100.088 +EDGE_SE3:QUAT 2244 2245 2.20503 -0.09637 -0.0172909 0.00277472 0.0257586 -0.0126298 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.864 -0.0078239 12.9285 399.732 -0.766535 100.453 +EDGE_SE3:QUAT 2245 2246 2.11452 -0.240469 -0.0303933 0.00502875 0.0194651 -0.0238127 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.491 -0.00642442 9.81249 399.84 -1.41501 100.219 +EDGE_SE3:QUAT 2246 2247 2.08407 -0.393739 -0.0400024 0.00625187 0.0289549 -0.0825625 0.996146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.11 -0.109338 14.7423 399.659 -1.39767 99.9298 +EDGE_SE3:QUAT 2247 2248 2.16682 -0.247001 -0.208535 0.000629041 0.0248252 -0.0597925 0.997902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.798 -0.0647554 12.4218 399.757 0.107028 100.073 +EDGE_SE3:QUAT 2248 2249 2.1459 -0.111355 0.0157882 -0.00814829 0.0291895 -0.0692772 0.997137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.01 -0.124863 14.2313 399.654 2.84362 100.114 +EDGE_SE3:QUAT 2249 2250 2.01073 -0.0475806 0.0156337 0.00349943 0.0240064 -0.0760837 0.996806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.757 -0.0715769 12.125 399.77 -0.684681 99.8327 +EDGE_SE3:QUAT 2250 2251 2.12883 -0.174054 -0.0828055 0.0053471 0.0222569 -0.065291 0.997604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.654 -0.047488 11.3152 399.794 -1.31328 99.9365 +EDGE_SE3:QUAT 2251 2252 2.08477 0.0094325 0.194089 0.00383639 0.0201091 -0.046784 0.998695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.53 -0.0267015 10.157 399.834 -0.962592 100.072 +EDGE_SE3:QUAT 2252 2253 2.12322 -0.15965 -0.0210489 -0.000516298 0.0170138 -0.079461 0.996693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.367 -0.0416989 8.44228 399.888 0.426042 99.5685 +EDGE_SE3:QUAT 2253 2254 2.2382 -0.290356 0.145082 -0.0038155 0.0244255 -0.0731668 0.997013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.735 -0.0854281 12.0101 399.766 1.50072 99.8755 +EDGE_SE3:QUAT 2254 2255 2.02312 -0.2504 0.0288613 -0.00664973 0.0148472 -0.0586606 0.998145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.246 -0.0312583 7.17144 399.902 2.16932 99.8159 +EDGE_SE3:QUAT 2255 2256 1.94161 -0.195137 -0.0529264 0.00163376 0.0182833 -0.0801932 0.99661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.435 -0.0455271 9.17799 399.869 -0.196392 99.5923 +EDGE_SE3:QUAT 2256 2257 2.05382 -0.316164 -0.000388159 -0.00483206 0.0349832 -0.0108554 0.999317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.58 -0.0416008 17.5325 399.505 1.51992 100.853 +EDGE_SE3:QUAT 2257 2258 1.97607 -0.347581 -0.118434 -0.00654688 0.0157394 -0.0344008 0.999263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.291 -0.0249429 7.73224 399.89 2.07132 100.063 +EDGE_SE3:QUAT 2258 2259 1.89973 -0.111151 -0.179496 -0.000337204 0.0211549 -0.035748 0.999137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.579 -0.0294849 10.5745 399.822 0.251635 100.185 +EDGE_SE3:QUAT 2259 2260 2.01897 -0.0903023 -0.136324 -0.00100726 0.0187092 -0.0312091 0.999337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.452 -0.0214939 9.33886 399.861 0.418329 100.147 +EDGE_SE3:QUAT 2260 2261 2.12452 -0.0722184 -0.164085 0.000413535 0.0138495 -0.0407987 0.999071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.249 -0.0135204 6.92912 399.924 -0.0111208 99.9678 +EDGE_SE3:QUAT 2261 2262 1.90337 -0.126811 -0.134714 0.00787324 0.0223832 -0.067099 0.997464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.662 -0.0446091 11.4838 399.781 -2.06094 99.9313 +EDGE_SE3:QUAT 2262 2263 1.99664 -0.107199 -0.0734655 0.006487 0.032282 -0.0783783 0.99638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.378 -0.129008 16.4178 399.577 -1.44083 100.143 +EDGE_SE3:QUAT 2263 2264 2.08043 -0.227108 -0.0959392 0.00472128 0.0197947 -0.0734679 0.99709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.518 -0.0436726 10.0713 399.838 -1.12533 99.7473 +EDGE_SE3:QUAT 2264 2265 1.99483 -0.145478 -0.0256797 -0.000969054 0.0226206 -0.080484 0.996499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.648 -0.0751801 11.2171 399.802 0.654786 99.7052 +EDGE_SE3:QUAT 2265 2266 2.01374 -0.191152 -0.200787 -0.00120804 0.0191121 -0.0565704 0.998215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.466 -0.0390934 9.49941 399.856 0.5782 99.9335 +EDGE_SE3:QUAT 2266 2267 1.93553 -0.221268 -0.12302 -0.00576392 0.0252957 -0.0498321 0.998421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.788 -0.0704725 12.4735 399.74 1.9779 100.2 +EDGE_SE3:QUAT 2267 2268 2.02526 -0.123949 -0.13481 0.00556123 0.0191539 -0.0753561 0.996957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.487 -0.0405569 9.7921 399.845 -1.37947 99.7058 +EDGE_SE3:QUAT 2268 2269 1.92607 -0.224127 0.0275058 -0.0028679 0.00726869 -0.0408305 0.999136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.062 -0.00575713 3.55926 399.977 0.919913 99.8716 +EDGE_SE3:QUAT 2269 2270 2.04498 -0.12889 -0.0343222 0.00176959 0.0184747 -0.064764 0.997728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.445 -0.0367792 9.28232 399.865 -0.291558 99.8215 +EDGE_SE3:QUAT 2270 2271 2.17281 -0.255601 -0.000481343 0.00632348 0.0240536 -0.0786653 0.996591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.768 -0.0689338 12.2835 399.759 -1.51834 99.8092 +EDGE_SE3:QUAT 2271 2272 1.99601 -0.159212 -0.152885 -9.62168e-05 0.0179682 -0.0471296 0.998727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.417 -0.0274909 8.97345 399.872 0.197889 100.003 +EDGE_SE3:QUAT 2272 2273 1.90808 -0.15794 0.107742 -0.00135041 0.0142354 -0.0650782 0.997778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.255 -0.0251872 7.04271 399.921 0.5908 99.7165 +EDGE_SE3:QUAT 2273 2274 1.94003 -0.103868 -0.0945336 -0.00408839 0.0129228 -0.0423197 0.999012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.201 -0.0174916 6.35062 399.93 1.33572 99.9399 +EDGE_SE3:QUAT 2274 2275 1.99659 -0.119079 0.0962734 -0.00270449 0.0248616 -0.03115 0.999202 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.792 -0.041273 12.3957 399.753 0.964036 100.335 +EDGE_SE3:QUAT 2275 2276 2.00207 -0.192687 0.00795414 -0.000485173 0.0129039 -0.0389626 0.999157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.215 -0.0122483 6.43548 399.934 0.246019 99.9643 +EDGE_SE3:QUAT 2276 2277 2.07027 -0.234872 -0.0713098 0.00150018 0.0213073 -0.0434141 0.998829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.592 -0.0324147 10.6917 399.819 -0.265424 100.131 +EDGE_SE3:QUAT 2277 2278 1.69467 -0.280225 -0.125107 -0.00615592 0.0215561 -0.0600198 0.997945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.555 -0.0611481 10.5371 399.809 2.10402 99.9654 +EDGE_SE3:QUAT 2278 2279 1.93965 -0.285605 0.02596 0.00919075 0.0260695 -0.0443801 0.998632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.885 -0.0308387 13.2885 399.701 -2.52347 100.317 +EDGE_SE3:QUAT 2279 2280 2.10948 -0.229895 0.0235473 0.00677237 0.0115201 -0.0790685 0.99678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.174 -0.0121259 6.05129 399.932 -1.85006 99.4881 +EDGE_SE3:QUAT 2280 2281 1.90619 -0.125626 -0.0514883 -0.00665273 0.0163339 -0.0783426 0.99677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.294 -0.0449491 7.81572 399.886 2.25328 99.5746 +EDGE_SE3:QUAT 2281 2282 1.90665 -0.151257 0.0525089 -0.00533757 0.0220696 -0.0751995 0.99691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.581 -0.0743862 10.7547 399.805 1.93275 99.7708 +EDGE_SE3:QUAT 2282 2283 2.00813 -0.125643 0.000770173 0.00201606 0.0161384 -0.0439941 0.998899 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.341 -0.0175158 8.11581 399.895 -0.462829 99.9913 +EDGE_SE3:QUAT 2283 2284 1.82385 -0.233781 -0.124276 -0.000226398 0.0193822 -0.0482684 0.998646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.485 -0.0329766 9.67681 399.852 0.25452 100.029 +EDGE_SE3:QUAT 2284 2285 1.70843 -0.0746772 0.0935637 0.00314347 0.0168066 -0.0311052 0.99937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.368 -0.0106139 8.4631 399.884 -0.83825 100.106 +EDGE_SE3:QUAT 2285 2286 1.77948 -0.077969 -0.067751 0.00548583 0.0194367 -0.0460221 0.998736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.494 -0.0210548 9.86451 399.84 -1.46634 100.067 +EDGE_SE3:QUAT 2286 2287 1.98606 -0.383365 -0.00625424 0.00561707 0.0152686 -0.0452028 0.998845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.303 -0.0106919 7.77898 399.897 -1.54677 99.9726 +EDGE_SE3:QUAT 2287 2288 1.79612 -0.220759 -0.251684 0.00559607 0.010936 -0.0349138 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.15 -0.00143866 5.58151 399.942 -1.60228 99.9737 +EDGE_SE3:QUAT 2288 2289 1.99977 -0.205718 -0.000534324 -0.00597001 0.0201344 -0.0516858 0.998443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.487 -0.0481709 9.87078 399.832 1.99767 100.019 +EDGE_SE3:QUAT 2289 2290 1.7525 -0.0631915 -0.185304 0.00121452 0.0189308 -0.0396909 0.999032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.467 -0.0233837 9.49282 399.857 -0.214315 100.094 +EDGE_SE3:QUAT 2290 2291 1.68723 0.0242981 -0.00989759 0.00587571 0.0237213 -0.0864803 0.995954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.747 -0.0761188 12.1098 399.768 -1.3521 99.6666 +EDGE_SE3:QUAT 2291 2292 1.66644 -0.24247 -0.0224895 -0.00932076 0.0262005 -0.051976 0.998261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.807 -0.0856208 12.8053 399.708 3.06359 100.22 +EDGE_SE3:QUAT 2292 2293 2.01819 -0.343416 -0.193556 6.47008e-05 0.0181029 -0.0435635 0.998887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.424 -0.0255478 9.04799 399.87 0.137954 100.039 +EDGE_SE3:QUAT 2293 2294 1.75246 -0.16815 -0.0230253 0.00465389 0.0288781 -0.0628994 0.997591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.097 -0.0821732 14.6064 399.663 -1.03343 100.203 +EDGE_SE3:QUAT 2294 2295 1.93289 -0.239617 -0.0117727 0.00240956 0.0148663 -0.0390612 0.999123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.289 -0.0120779 7.48524 399.91 -0.60667 100.005 +EDGE_SE3:QUAT 2295 2296 1.77148 -0.118496 -0.0111194 0.000507099 0.0210432 -0.0599314 0.997981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.573 -0.0466554 10.522 399.826 0.099637 99.9502 +EDGE_SE3:QUAT 2296 2297 1.81996 -0.186001 -0.0486902 -0.0017746 0.00917657 -0.0543727 0.998477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.104 -0.00961364 4.51949 399.966 0.632513 99.7629 +EDGE_SE3:QUAT 2297 2298 1.77331 -0.0498224 0.0217255 -0.00429647 0.0176251 -0.046192 0.998768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.382 -0.03262 8.68544 399.873 1.45096 100.005 +EDGE_SE3:QUAT 2298 2299 1.65931 -0.292628 0.0578421 -0.000785856 0.0239878 -0.0873745 0.995886 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.727 -0.0909611 11.8935 399.779 0.655062 99.6331 +EDGE_SE3:QUAT 2299 2300 1.77318 -0.310941 -0.174551 0.000957869 0.0104149 -0.0651117 0.997823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.141 -0.0117878 5.22695 399.957 -0.151475 99.6525 +EDGE_SE3:QUAT 2300 2301 1.72243 -0.172336 -0.109753 0.00285789 0.0188787 -0.0865768 0.996062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.468 -0.0509714 9.53587 399.859 -0.529855 99.5051 +EDGE_SE3:QUAT 2301 2302 1.7992 -0.224403 -0.0128009 -0.00131265 0.00664736 -0.0610279 0.998113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.054 -0.00555004 3.26501 399.982 0.475387 99.6582 +EDGE_SE3:QUAT 2302 2303 1.75965 -0.249577 0.136034 -0.00123987 0.0263819 -0.0693176 0.997245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.886 -0.0891493 13.1134 399.729 0.735887 100.002 +EDGE_SE3:QUAT 2303 2304 1.76409 -0.185013 -0.0770608 -0.00698721 0.0212574 -0.0213564 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.556 -0.0320139 10.5505 399.806 2.18425 100.282 +EDGE_SE3:QUAT 2304 2305 1.83324 -0.282671 -0.0339006 0.00483099 0.0171253 -0.0991565 0.994913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.391 -0.0460295 8.7829 399.878 -1.10892 99.2357 +EDGE_SE3:QUAT 2305 2306 1.74034 -0.035354 -0.121631 0.00769164 0.0185377 -0.0110502 0.999738 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.429 0.0076627 9.32972 399.844 -2.26468 100.248 +EDGE_SE3:QUAT 2306 2307 1.8047 -0.200601 0.0310601 0.00357877 0.0195579 -0.0692666 0.9974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.504 -0.0414748 9.89877 399.845 -0.802578 99.7958 +EDGE_SE3:QUAT 2307 2308 1.57613 -0.160179 -0.0209339 -0.00387971 0.0158396 -0.0701466 0.997403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.301 -0.0362557 7.72783 399.899 1.38679 99.6817 +EDGE_SE3:QUAT 2308 2309 1.64404 0.108162 -0.117034 0.00368203 0.016314 -0.0568238 0.998244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.35 -0.0216704 8.2666 399.89 -0.919103 99.8707 +EDGE_SE3:QUAT 2309 2310 1.58565 -0.225276 0.10022 -0.00267658 0.019382 -0.0678828 0.997501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.467 -0.0498494 9.55381 399.852 1.06597 99.7984 +EDGE_SE3:QUAT 2310 2311 1.67408 -0.316932 -0.086084 -0.00559582 0.0181628 -0.0492522 0.998606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.396 -0.0381697 8.90568 399.862 1.85668 99.9911 +EDGE_SE3:QUAT 2311 2312 1.57609 -0.130485 -0.220239 -0.00157352 0.0192349 -0.0481506 0.998654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.472 -0.0347651 9.56403 399.854 0.656595 100.025 +EDGE_SE3:QUAT 2312 2313 1.55001 -0.254157 -0.0226944 0.000735609 0.0148204 -0.0715381 0.997327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.284 -0.0271945 7.41328 399.914 -0.0082225 99.6418 +EDGE_SE3:QUAT 2313 2314 1.68585 -0.216812 -0.106093 -0.00217745 0.0126911 -0.0326744 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.204 -0.0120947 6.30021 399.935 0.735943 100.006 +EDGE_SE3:QUAT 2314 2315 1.69411 -0.059591 0.00311116 0.00618885 0.0241454 -0.054317 0.998213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.767 -0.0429576 12.2678 399.756 -1.59375 100.133 +EDGE_SE3:QUAT 2315 2316 1.53893 -0.309835 -0.115086 0.000929497 0.0171309 -0.0637111 0.997821 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.381 -0.0321175 8.57844 399.884 -0.0604939 99.7998 +EDGE_SE3:QUAT 2316 2317 1.58762 -0.01135 0.0382817 -0.00585797 0.019327 -0.0306081 0.999327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.459 -0.0314257 9.55951 399.842 1.8739 100.174 +EDGE_SE3:QUAT 2317 2318 1.65334 -0.288916 0.0574487 -0.00719233 0.0278612 -0.070898 0.997068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.926 -0.114451 13.5952 399.687 2.5488 100.036 +EDGE_SE3:QUAT 2318 2319 1.69819 -0.236228 -0.115156 0.00327548 0.0205653 -0.0710043 0.997259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.556 -0.0480847 10.391 399.83 -0.690534 99.7987 +EDGE_SE3:QUAT 2319 2320 1.5934 -0.0217161 -0.0405252 0.0102547 0.0204667 -0.020076 0.999536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.518 0.00625589 10.3679 399.8 -2.99142 100.29 +EDGE_SE3:QUAT 2320 2321 1.60879 0.0145946 -0.0767824 -0.00411855 0.00989954 -0.102361 0.99469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.103 -0.019848 4.65228 399.959 1.44196 99.0199 +EDGE_SE3:QUAT 2321 2322 1.6329 -0.0530947 -0.150271 -0.00307054 0.00872835 -0.0778761 0.99692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.086 -0.0124813 4.19813 399.968 1.05856 99.4467 +EDGE_SE3:QUAT 2322 2323 1.46763 -0.112863 0.0644892 0.00458662 0.0230209 -0.0620643 0.997796 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.698 -0.0495805 11.6633 399.783 -1.09017 99.9982 +EDGE_SE3:QUAT 2323 2324 1.53786 -0.263344 0.106711 -0.0075766 0.0177117 -0.0295546 0.999378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.37 -0.0294525 8.72322 399.859 2.37589 100.145 +EDGE_SE3:QUAT 2324 2325 1.51244 -0.249677 -0.18187 -0.000410995 0.0151048 -0.0286519 0.999475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.295 -0.0123683 7.54575 399.909 0.209617 100.077 +EDGE_SE3:QUAT 2325 2326 1.49086 -0.176673 0.228074 -0.00418207 0.0181173 -0.0562537 0.998243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.401 -0.0396325 8.90133 399.867 1.45793 99.9125 +EDGE_SE3:QUAT 2326 2327 1.53129 -0.0755849 -0.00869481 0.00299193 0.0142522 -0.0713596 0.997344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.268 -0.0223478 7.22664 399.917 -0.693977 99.6382 +EDGE_SE3:QUAT 2327 2328 1.3665 -0.342648 0.021883 0.0014112 0.0159042 -0.0609394 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.33 -0.0256553 7.98419 399.9 -0.229436 99.807 +EDGE_SE3:QUAT 2328 2329 1.63015 -0.326397 -0.136252 -0.001146 0.0122392 -0.0439123 0.99896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.191 -0.0131027 6.08192 399.941 0.451276 99.9114 +EDGE_SE3:QUAT 2329 2330 1.39417 -0.0359897 -0.0200153 -0.0124121 0.0179194 -0.0310261 0.999281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.33 -0.0386092 8.72869 399.829 3.83197 100.166 +EDGE_SE3:QUAT 2330 2331 1.44161 0.0638514 -0.0118146 -0.000394657 0.0143188 -0.0899371 0.995844 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.259 -0.0331751 7.09096 399.921 0.37747 99.3322 +EDGE_SE3:QUAT 2331 2332 1.68199 -0.134449 -0.0126487 -0.00875763 0.018792 -0.0691676 0.99739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.383 -0.0561897 9.00163 399.843 2.88727 99.7767 +EDGE_SE3:QUAT 2332 2333 1.48244 -0.169052 -0.0362219 0.000614431 0.0160261 -0.0448443 0.998865 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.334 -0.0197707 8.02229 399.898 -0.0407277 99.9789 +EDGE_SE3:QUAT 2333 2334 1.41509 -0.299297 -0.000997348 0.0040579 0.0124643 -0.064028 0.997862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.205 -0.0133354 6.36842 399.933 -1.05777 99.7069 +EDGE_SE3:QUAT 2334 2335 1.36312 -0.0447894 -0.00277897 0.00196625 0.0241357 -0.0725754 0.997069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.758 -0.0717515 12.1209 399.771 -0.24002 99.8835 +EDGE_SE3:QUAT 2335 2336 1.43872 -0.108667 -0.0950942 0.00102848 0.00527631 -0.0632176 0.997985 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.037 -0.00267828 2.66789 399.989 -0.241773 99.6204 +EDGE_SE3:QUAT 2336 2337 1.38383 -0.146216 -0.0210355 0.00837153 0.00719242 -0.0486587 0.998754 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.05 0.00161612 3.83337 399.957 -2.44189 99.824 +EDGE_SE3:QUAT 2337 2338 1.50331 -0.0553864 -0.124124 0.00320104 0.0243301 -0.0833804 0.996216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.775 -0.0821249 12.2745 399.766 -0.554603 99.7259 +EDGE_SE3:QUAT 2338 2339 1.50281 -0.18568 -0.0580225 -0.00228867 0.0157606 -0.02499 0.999561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.317 -0.0146991 7.84823 399.9 0.764817 100.112 +EDGE_SE3:QUAT 2339 2340 1.48423 -0.264846 -0.055099 0.0050745 0.0225785 -0.0480344 0.998578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.669 -0.0331484 11.4328 399.789 -1.30501 100.14 +EDGE_SE3:QUAT 2340 2341 1.36485 -0.0976642 -0.180627 0.00488706 0.0174939 -0.0533818 0.998409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.402 -0.0213863 8.8907 399.87 -1.27911 99.9411 +EDGE_SE3:QUAT 2341 2342 1.53194 -0.182039 -0.0876279 -0.00375382 0.0225378 -0.0606005 0.997901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.631 -0.0624147 11.1139 399.798 1.39787 99.9848 +EDGE_SE3:QUAT 2342 2343 1.5589 -0.0554465 0.0256605 0.00398546 0.0150854 -0.0804914 0.996633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.302 -0.0279075 7.6972 399.905 -0.952536 99.5204 +EDGE_SE3:QUAT 2343 2344 1.48766 -0.196837 0.0568543 0.00552012 0.0151717 -0.0516189 0.998536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.301 -0.0134515 7.7449 399.898 -1.4992 99.9084 +EDGE_SE3:QUAT 2344 2345 1.4279 -0.253921 0.126671 -0.00223843 0.0106551 -0.119828 0.992735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.13 -0.0248754 5.10033 399.957 0.93159 98.6399 +EDGE_SE3:QUAT 2345 2346 1.42564 -0.1609 -0.0943723 0.0036829 0.00720027 -0.0974671 0.995206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.07 -0.00706142 3.78483 399.975 -0.96483 99.0929 +EDGE_SE3:QUAT 2346 2347 1.44731 -0.314619 0.00473586 -0.00106825 0.0194054 -0.0634151 0.997798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.479 -0.0445345 9.63936 399.853 0.566322 99.8587 +EDGE_SE3:QUAT 2347 2348 1.3885 -0.162676 -0.0752585 -0.0029832 0.0176399 -0.09134 0.995659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.375 -0.0539683 8.59921 399.88 1.21924 99.3777 +EDGE_SE3:QUAT 2348 2349 1.53003 -0.0655569 -0.034423 -0.0107132 0.017073 -0.0167612 0.999656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.322 -0.0266927 8.43397 399.85 3.26867 100.207 +EDGE_SE3:QUAT 2349 2350 1.17426 -0.271174 0.058394 -0.0044862 0.0233131 -0.0260613 0.999378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.688 -0.0358119 11.6007 399.778 1.46494 100.316 +EDGE_SE3:QUAT 2350 2351 1.50233 -0.019349 -0.00954614 0.00235827 0.0154515 -0.0494259 0.998655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.313 -0.0178051 7.78522 399.903 -0.554709 99.9261 +EDGE_SE3:QUAT 2351 2352 1.5122 -0.0827326 -0.0294347 0.0103831 0.0100966 -0.0680635 0.997576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.114 -0.00240804 5.45259 399.925 -2.97837 99.6488 +EDGE_SE3:QUAT 2352 2353 1.27187 -0.00353359 0.00199358 -0.000156899 0.0188096 -0.0581249 0.998132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.455 -0.0371336 9.3822 399.861 0.265459 99.9085 +EDGE_SE3:QUAT 2353 2354 1.531 -0.251894 -0.0897503 -0.0026959 0.0153842 -0.0750166 0.99706 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.289 -0.0348517 7.53781 399.907 1.0405 99.6 +EDGE_SE3:QUAT 2354 2355 1.34621 -0.265306 -0.105326 0.00251609 0.0118647 -0.0532409 0.998508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.185 -0.0107085 6.00054 399.942 -0.62845 99.8185 +EDGE_SE3:QUAT 2355 2356 1.29027 -0.167265 -0.0110243 -0.00540527 0.0153576 -0.0919795 0.995628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.261 -0.0436409 7.32783 399.904 1.90707 99.3167 +EDGE_SE3:QUAT 2356 2357 1.43467 -0.134558 -0.159444 -0.00414388 0.0178047 -0.0496431 0.9986 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.39 -0.0348236 8.76835 399.871 1.41922 99.9755 +EDGE_SE3:QUAT 2357 2358 1.39576 -0.167194 0.103494 -0.00380877 0.0220177 -0.0617609 0.997841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.6 -0.0607599 10.8474 399.807 1.41337 99.9544 +EDGE_SE3:QUAT 2358 2359 1.31826 -0.0968099 0.107417 0.00830874 0.0144208 -0.0557432 0.998306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.265 -0.00943817 7.47344 399.895 -2.33165 99.863 +EDGE_SE3:QUAT 2359 2360 1.26694 -0.164646 0.0728221 0.00726248 0.0242532 -0.0845235 0.9961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.784 -0.0748672 12.443 399.752 -1.76834 99.727 +EDGE_SE3:QUAT 2360 2361 1.13627 -0.0887732 -0.0331629 0.000232768 0.0139744 -0.0631317 0.997907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.252 -0.0217922 6.97566 399.923 0.106861 99.7376 +EDGE_SE3:QUAT 2361 2362 1.34974 -0.271104 -0.0434743 -0.00343447 0.00212248 -0.0675313 0.997709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.999 -0.000988534 0.917933 399.995 1.0599 99.5501 +EDGE_SE3:QUAT 2362 2363 1.47457 -0.253676 0.0627284 0.00420092 0.0112914 -0.0386165 0.999181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.165 -0.00422729 5.73799 399.943 -1.17298 99.9474 +EDGE_SE3:QUAT 2363 2364 1.19429 -0.118742 -0.0226078 -0.00113857 0.0166383 -0.080844 0.996587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.348 -0.0413117 8.22273 399.893 0.611554 99.5368 +EDGE_SE3:QUAT 2364 2365 1.4409 -0.207449 0.222692 -0.00537295 0.0222288 -0.0585382 0.998023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.601 -0.0620817 10.909 399.8 1.87042 100.002 +EDGE_SE3:QUAT 2365 2366 1.27185 -0.118601 0.121173 -0.00575735 0.0097329 -0.0622588 0.997996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.096 -0.0149123 4.63585 399.954 1.84944 99.6842 +EDGE_SE3:QUAT 2366 2367 1.2889 -0.219168 -0.0358816 -0.00251773 0.010978 -0.0607588 0.998089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.147 -0.0154039 5.38119 399.951 0.889255 99.7146 +EDGE_SE3:QUAT 2367 2368 1.2469 -0.174755 -0.0505601 -0.000289604 0.0140378 -0.0796241 0.996726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.251 -0.0282858 6.96971 399.924 0.311336 99.5022 +EDGE_SE3:QUAT 2368 2369 1.42156 -0.106308 0.143844 0.00230648 0.0129937 -0.0778976 0.996874 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.222 -0.0210904 6.57296 399.932 -0.489128 99.5146 +EDGE_SE3:QUAT 2369 2370 1.12391 -0.18855 -0.235858 0.00571159 0.0127872 -0.0326931 0.999367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.208 -0.0023635 6.50318 399.924 -1.62952 100.02 +EDGE_SE3:QUAT 2370 2371 1.18916 -0.258598 -0.0428346 -0.00601876 0.0185984 -0.0775461 0.996797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.397 -0.0560009 8.97871 399.858 2.09493 99.6393 +EDGE_SE3:QUAT 2371 2372 1.20085 0.0183165 0.127728 -0.00646245 0.00875065 -0.0750459 0.997121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.067 -0.0140634 4.0634 399.959 2.07214 99.4976 +EDGE_SE3:QUAT 2372 2373 1.45807 -0.186217 -0.107362 -7.99562e-05 0.00959205 -0.0598617 0.998161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.118 -0.00992678 4.77921 399.964 0.139111 99.7056 +EDGE_SE3:QUAT 2373 2374 1.18426 0.000197157 -0.0344764 0.002492 0.00490747 -0.0802799 0.996757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.032 -0.00244055 2.55952 399.988 -0.669063 99.3752 +EDGE_SE3:QUAT 2374 2375 1.21769 -0.271659 -0.0521866 0.00186734 0.0146723 -0.0689438 0.997511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.282 -0.0242485 7.38753 399.914 -0.357639 99.6776 +EDGE_SE3:QUAT 2375 2376 1.26801 -0.20578 -0.324607 -0.00290275 0.0111804 -0.0514765 0.998607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.152 -0.0143715 5.48951 399.949 0.986173 99.8227 +EDGE_SE3:QUAT 2376 2377 1.1643 -0.231669 0.0395846 -0.00920797 0.00570058 -0.0896876 0.995911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.992 -0.0073618 2.33541 399.964 2.86879 99.2385 +EDGE_SE3:QUAT 2377 2378 1.0243 -0.0785003 0.00329079 -0.000680743 0.0146768 -0.0765559 0.996957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.273 -0.0301993 7.27377 399.916 0.429736 99.5625 +EDGE_SE3:QUAT 2378 2379 1.08363 -0.205519 -0.204391 -0.00154039 0.00756283 -0.0616172 0.99807 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.07 -0.00726951 3.71231 399.977 0.55583 99.66 +EDGE_SE3:QUAT 2379 2380 1.11237 -0.108409 0.194716 0.00399976 0.00946153 -0.011506 0.999881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.112 0.00195968 4.75926 399.959 -1.17792 100.055 +EDGE_SE3:QUAT 2380 2381 1.14711 -0.202115 0.0472177 -0.00264097 0.0086103 -0.0516189 0.998626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.089 -0.00882914 4.2141 399.969 0.881543 99.7859 +EDGE_SE3:QUAT 2381 2382 1.25781 -0.0421506 -0.25557 -0.00305602 0.0239178 -0.0709309 0.99719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.712 -0.0784985 11.7972 399.776 1.25488 99.8913 +EDGE_SE3:QUAT 2382 2383 1.14591 -0.198373 0.105221 0.00109753 0.0111621 -0.0923834 0.99566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.162 -0.0196098 5.60132 399.951 -0.121952 99.2342 +EDGE_SE3:QUAT 2383 2384 0.984793 -0.248879 -0.0517567 -0.00265551 0.0100793 -0.0533601 0.998521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.123 -0.0120263 4.94339 399.958 0.904568 99.7865 +EDGE_SE3:QUAT 2384 2385 1.16999 0.104466 -0.0044227 5.12999e-05 0.00965898 -0.0408734 0.999118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.121 -0.00680201 4.82505 399.963 0.063605 99.8981 +EDGE_SE3:QUAT 2385 2386 1.20208 -0.0420889 0.163314 0.00533399 0.00850505 -0.0363649 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.088 -0.000212209 4.36488 399.962 -1.53835 99.9288 +EDGE_SE3:QUAT 2386 2387 1.12047 -0.212918 -0.0587477 -0.000527168 0.0109779 -0.0539413 0.998484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.154 -0.0121641 5.45979 399.953 0.276774 99.7927 +EDGE_SE3:QUAT 2387 2388 1.1279 -0.189501 0.129593 -3.41439e-05 0.0294966 -0.0542973 0.998089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 401.124 -0.0850612 14.7525 399.657 0.327883 100.313 +EDGE_SE3:QUAT 2388 2389 1.32964 -0.14278 0.0983584 0.00016335 0.0158808 -0.0724865 0.997243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.324 -0.0324576 7.91685 399.902 0.181676 99.6499 +EDGE_SE3:QUAT 2389 2390 1.07822 -0.191734 -0.0171374 -0.00348472 0.0128142 -0.0384482 0.999172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.202 -0.0154814 6.32164 399.932 1.14373 99.9685 +EDGE_SE3:QUAT 2390 2391 1.07505 -0.15458 -0.111723 0.00205813 0.0129616 -0.0459992 0.998855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.22 -0.0113763 6.52913 399.932 -0.498161 99.9084 +EDGE_SE3:QUAT 2391 2392 1.11633 -0.0580665 -0.0592771 -0.00937755 0.0114935 -0.0200834 0.999688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.129 -0.0150762 5.63367 399.922 2.85854 100.076 +EDGE_SE3:QUAT 2392 2393 1.00544 -0.183941 0.00773578 0.0114018 0.0123611 -0.0347997 0.999253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.164 0.00483401 6.41488 399.898 -3.33368 100.031 +EDGE_SE3:QUAT 2393 2394 1.04601 -0.117857 -0.0362245 -0.00149546 0.00653651 -0.0722278 0.997366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.051 -0.00625467 3.18865 399.983 0.543844 99.5078 +EDGE_SE3:QUAT 2394 2395 1.05325 -0.0347048 -0.0441859 -0.00625124 0.00019409 -0.083383 0.996498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.985 0.000510852 -0.215585 399.988 1.88073 99.3166 +EDGE_SE3:QUAT 2395 2396 1.09705 -0.236036 -0.0712261 0.00561484 0.00623365 -0.0335645 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.042 0.00121337 3.2271 399.975 -1.6427 99.9254 +EDGE_SE3:QUAT 2396 2397 1.00937 -0.135622 0.1453 0.00535565 0.00460282 -0.0704233 0.997492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.022 -0.000300487 2.51725 399.982 -1.54275 99.5295 +EDGE_SE3:QUAT 2397 2398 0.881329 0.0668708 0.110495 0.0102711 0.00932981 -0.0461646 0.998837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.087 0.00254423 4.94159 399.932 -2.99531 99.8847 +EDGE_SE3:QUAT 2398 2399 1.18077 -0.0155792 0.0819929 -0.00436974 0.00876711 -0.0652976 0.997818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.082 -0.0119264 4.19668 399.965 1.42648 99.6299 +EDGE_SE3:QUAT 2399 2400 1.24287 -0.174488 0.0146951 -0.000944129 0.0074483 -0.0673878 0.997699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.069 -0.00724775 3.67149 399.978 0.384184 99.5841 +EDGE_SE3:QUAT 2400 2401 1.02689 0.0488939 -0.0107248 0.00501843 0.00565042 -0.0863512 0.996236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.04 -0.0025025 3.066 399.979 -1.40894 99.287 +EDGE_SE3:QUAT 2401 2402 0.922211 -0.142718 -0.00329857 -0.00204679 0.0173201 -0.0888057 0.995896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.369 -0.049811 8.49815 399.885 0.923304 99.4163 +EDGE_SE3:QUAT 2402 2403 0.948903 -0.100292 -0.118346 0.00622506 0.00608473 -0.0534832 0.998531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.04 0.000215291 3.2345 399.973 -1.80294 99.7539 +EDGE_SE3:QUAT 2403 2404 0.957981 -0.167713 -0.0817728 -0.00426144 0.0138346 -0.074611 0.997108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.222 -0.029867 6.69616 399.922 1.48614 99.5764 +EDGE_SE3:QUAT 2404 2405 0.966836 -0.0343883 -0.0641363 0.0122044 0.00374272 -0.0286269 0.999509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.964 0.00454471 2.07943 399.949 -3.63995 99.9742 +EDGE_SE3:QUAT 2405 2406 1.14955 -0.0517833 -0.0981234 0.00520759 0.00681898 -0.0518077 0.99862 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.056 -0.000867549 3.56357 399.973 -1.49196 99.7744 +EDGE_SE3:QUAT 2406 2407 0.880208 -0.116449 0.0152669 0.000513511 0.0119182 -0.0379216 0.99921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.185 -0.00909753 5.96604 399.943 -0.063681 99.9558 +EDGE_SE3:QUAT 2407 2408 0.779758 -0.231602 -0.0116363 -0.00425329 0.00175384 -0.0720165 0.997393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.995 -0.000741024 0.689353 399.994 1.30245 99.4884 +EDGE_SE3:QUAT 2408 2409 0.937779 -0.265218 -0.0727954 0.00717363 0.0149747 -0.0701764 0.997396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.295 -0.0187116 7.76217 399.894 -1.94197 99.6879 +EDGE_SE3:QUAT 2409 2410 0.860547 -0.180693 -0.0319612 0.0058168 0.00635236 -0.0194692 0.999773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.041 0.00236253 3.24343 399.973 -1.72021 100.001 +EDGE_SE3:QUAT 2410 2411 0.970943 -0.0328469 0.0245733 3.64076e-05 0.0105749 -0.0597218 0.998159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.144 -0.0119254 5.27383 399.956 0.115653 99.7212 +EDGE_SE3:QUAT 2411 2412 0.910464 -0.176781 -0.0160987 0.0138363 0.0154835 -0.0960283 0.995162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.304 -0.0237199 8.48019 399.843 -3.8549 99.3263 +EDGE_SE3:QUAT 2412 2413 0.716215 -0.0672759 -0.180584 -0.00480139 0.0133469 -0.0231592 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.217 -0.0136318 6.60735 399.923 1.50161 100.076 +EDGE_SE3:QUAT 2413 2414 1.06891 -0.0613279 -0.0121096 0.00054539 0.0108289 -0.0633034 0.997935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.152 -0.0127805 5.41785 399.954 -0.0262353 99.6814 +EDGE_SE3:QUAT 2414 2415 0.768765 -0.234965 0.115413 -0.00704542 0.0117853 -0.0605169 0.998073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.141 -0.0215984 5.6198 399.932 2.25712 99.7395 +EDGE_SE3:QUAT 2415 2416 0.809282 -0.174424 -0.0118621 -0.00151672 0.00623272 -0.0882387 0.996079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.046 -0.00671091 3.01481 399.985 0.566351 99.2479 +EDGE_SE3:QUAT 2416 2417 0.995156 -0.209479 -0.00575775 0.00559308 0.00613329 -0.0764586 0.997038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.045 -0.00204153 3.30706 399.975 -1.58505 99.4541 +EDGE_SE3:QUAT 2417 2418 0.779909 -0.0498183 0.0623948 0.000907299 0.00795609 -0.0340501 0.999388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.083 -0.00317781 3.99331 399.974 -0.218 99.9288 +EDGE_SE3:QUAT 2418 2419 0.899306 0.0789548 -0.00625073 0.0109768 0.0092122 -0.0751764 0.997067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.089 -0.00180001 5.07837 399.928 -3.15598 99.5394 +EDGE_SE3:QUAT 2419 2420 0.74652 -0.23748 -0.00681759 0.00614939 0.00605444 -0.0798767 0.996767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.043 -0.00186817 3.30438 399.973 -1.74923 99.4024 +EDGE_SE3:QUAT 2420 2421 0.936316 -0.120846 0.00285827 0.00634807 0.0158799 -0.0855316 0.996189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.337 -0.0305224 8.22041 399.887 -1.63274 99.4655 +EDGE_SE3:QUAT 2421 2422 1.09531 -0.165679 0.0372133 0.00663681 0.0136655 -0.040568 0.999061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.238 -0.0047202 6.98872 399.911 -1.8798 99.9835 +EDGE_SE3:QUAT 2422 2423 0.806983 -0.102447 0.0695419 0.00386535 0.0059436 -0.0442586 0.998995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.043 -0.000555278 3.06952 399.981 -1.10718 99.8345 +EDGE_SE3:QUAT 2423 2424 0.930682 -0.290974 0.0122849 -0.0047107 0.00434128 -0.0546455 0.998485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.012 -0.00341261 2.01057 399.986 1.46141 99.7199 +EDGE_SE3:QUAT 2424 2425 1.0523 -0.0942562 -0.0467388 -0.0030191 0.00274119 -0.0959255 0.99538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.003 -0.00164613 1.18603 399.995 0.960136 99.0869 +EDGE_SE3:QUAT 2425 2426 0.824703 -0.109445 0.0693976 -0.0054266 0.0152345 -0.0454711 0.998835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.275 -0.0263416 7.46058 399.901 1.76605 99.9596 +EDGE_SE3:QUAT 2426 2427 0.75497 -0.0782575 -0.0804936 -0.0114118 0.0166326 -0.0385623 0.999053 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.28 -0.0362153 8.04727 399.854 3.54998 100.075 +EDGE_SE3:QUAT 2427 2428 0.96138 -0.188054 0.0592043 0.00776214 0.0121902 -0.0226944 0.999638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.177 0.00352502 6.20104 399.922 -2.27263 100.073 +EDGE_SE3:QUAT 2428 2429 0.9152 -0.0855797 -0.0600578 0.00868677 0.00597835 -0.0348163 0.999338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.023 0.00323235 3.16757 399.962 -2.56454 99.9286 +EDGE_SE3:QUAT 2429 2430 0.850647 -0.129926 -0.0223232 0.00776117 0.0115659 -0.0485532 0.998723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.165 -0.00290189 5.9994 399.927 -2.216 99.881 +EDGE_SE3:QUAT 2430 2431 0.685435 -0.133605 0.077878 0.00038103 0.00188602 -0.0760089 0.997105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.005 -0.000424716 0.955466 399.999 -0.085581 99.4248 +EDGE_SE3:QUAT 2431 2432 0.823047 -0.149762 -0.162131 0.000585858 0.00540603 -0.0531413 0.998572 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.038 -0.00249825 2.71509 399.988 -0.11823 99.7383 +EDGE_SE3:QUAT 2432 2433 0.840293 -0.239467 -0.135264 -0.00702109 0.00456955 -0.0488514 0.998771 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 -0.00426388 2.07425 399.978 2.15176 99.7889 +EDGE_SE3:QUAT 2433 2434 0.705048 -0.335835 0.136846 0.00456307 0.00680482 -0.0866791 0.996203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.061 -0.00462134 3.61678 399.975 -1.25164 99.2902 +EDGE_SE3:QUAT 2434 2435 0.707182 -0.05967 0.1415 -0.000135478 0.00578721 -0.066834 0.997747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.043 -0.00406508 2.87688 399.987 0.118339 99.5765 +EDGE_SE3:QUAT 2435 2436 0.77111 -0.274935 -0.0170584 -0.000271295 0.00724299 -0.0897192 0.995941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.066 -0.00849739 3.58134 399.98 0.212413 99.2311 +EDGE_SE3:QUAT 2436 2437 0.741301 -0.188334 0.027943 0.000526433 0.00400773 -0.0566174 0.998388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.021 -0.00144139 2.01607 399.994 -0.11249 99.6909 +EDGE_SE3:QUAT 2437 2438 0.718309 -0.043868 -0.132531 -0.00231343 0.0108218 -0.0492107 0.998727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.145 -0.0125593 5.33291 399.953 0.800719 99.8396 +EDGE_SE3:QUAT 2438 2439 0.927783 -0.188973 0.0167979 -0.0013889 0.00962122 -0.0857028 0.996273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.113 -0.0150373 4.70899 399.964 0.583015 99.3287 +EDGE_SE3:QUAT 2439 2440 0.637889 -0.127063 -0.0647379 0.000718761 0.00937236 -0.0859208 0.996258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.114 -0.0129429 4.69347 399.966 -0.0537801 99.3233 +EDGE_SE3:QUAT 2440 2441 0.773295 -0.258757 -0.095237 0.00492273 0.00404014 -0.0499132 0.998733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.015 0.000567433 2.16295 399.986 -1.43692 99.7707 +EDGE_SE3:QUAT 2441 2442 0.62647 -0.178776 0.0682368 -0.00159236 0.00793988 -0.0649013 0.997859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.077 -0.00834027 3.89377 399.975 0.581382 99.6224 +EDGE_SE3:QUAT 2442 2443 0.676178 -0.102123 0.104527 0.00543922 0.0219341 -0.0614907 0.997852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.634 -0.0423408 11.1495 399.799 -1.36174 99.9748 +EDGE_SE3:QUAT 2443 2444 0.632994 -0.274214 -0.0604122 0.000930496 0.00713197 -0.0592778 0.998216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.067 -0.00481604 3.58841 399.98 -0.194481 99.6847 +EDGE_SE3:QUAT 2444 2445 0.623687 -0.326872 0.105519 -0.00266444 0.0134454 -0.0495575 0.998677 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.224 -0.0192613 6.63265 399.927 0.932594 99.8805 +EDGE_SE3:QUAT 2445 2446 0.773107 -0.0253377 0.182962 0.00665332 -0.00568202 -0.0408613 0.999127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.019 -0.00554486 -2.67385 399.974 -2.04286 99.8671 +EDGE_SE3:QUAT 2446 2447 0.673561 -0.154025 -0.0901807 -0.0102883 -0.00644118 -0.10021 0.994892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.036 -0.00145869 -3.8086 399.95 2.96065 99.0648 +EDGE_SE3:QUAT 2447 2448 0.411284 -0.20703 0.136687 0.00574554 -0.00215232 -0.0455881 0.998941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.991 -0.00121853 -0.917078 399.988 -1.74388 99.8047 +EDGE_SE3:QUAT 2448 2449 0.672445 0.0464331 -0.0631548 -0.0022213 0.0107247 -0.0899152 0.995889 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.137 -0.0199285 5.20571 399.955 0.861244 99.2699 +EDGE_SE3:QUAT 2449 2450 0.665612 -0.205443 -0.135734 0.00281588 0.00649121 -0.023624 0.999696 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.053 3.68188e-05 3.28436 399.981 -0.814078 99.9766 +EDGE_SE3:QUAT 2450 2451 0.615586 -0.0372146 0.0863717 0.00206434 0.00173385 -0.062296 0.998054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.003 1.8567e-05 0.940967 399.997 -0.598007 99.6156 +EDGE_SE3:QUAT 2451 2452 0.579888 -0.059038 0.0357022 0.0124908 -0.000488584 -0.0676974 0.997628 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.938 0.00148323 0.263305 399.953 -3.75642 99.5888 +EDGE_SE3:QUAT 2452 2453 0.578913 -0.045787 -0.013608 0.00941819 0.00824171 -0.0392333 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.064 0.00320531 4.33761 399.945 -2.76083 99.9239 +EDGE_SE3:QUAT 2453 2454 0.706556 -0.09142 -0.0870603 -0.00408096 -0.00142772 -0.0507622 0.998701 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.997 0.000501832 -0.836393 399.994 1.21026 99.7491 +EDGE_SE3:QUAT 2454 2455 0.3758 -0.147899 0.0169202 0.00299847 0.0097578 -0.0754178 0.9971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.126 -0.0104107 4.9911 399.959 -0.752331 99.5026 +EDGE_SE3:QUAT 2455 2456 0.568694 -0.038551 0.00840634 0.00716426 0.00252344 -0.0852027 0.996335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.994 0.0011304 1.61885 399.981 -2.10841 99.296 +EDGE_SE3:QUAT 2456 2457 0.593057 0.068819 0.0774987 0.00376772 0.00744913 -0.0656496 0.997808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.072 -0.00400421 3.8591 399.973 -1.03279 99.6141 +EDGE_SE3:QUAT 2457 2458 0.498043 -0.0344245 -0.0750707 0.00321829 0.00417847 -0.0737801 0.997261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.022 -0.00109992 2.22136 399.99 -0.90432 99.4721 +EDGE_SE3:QUAT 2458 2459 0.582558 -0.0429044 0.070323 0.0101884 0.00184917 -0.0778613 0.99691 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.969 0.00246961 1.3945 399.967 -3.03039 99.4295 +EDGE_SE3:QUAT 2459 2460 0.386098 -0.36747 -0.134591 0.0024098 0.00574322 -0.0473954 0.998857 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.043 -0.00148874 2.93463 399.985 -0.668607 99.8009 +EDGE_SE3:QUAT 2460 2461 0.517445 -0.176057 -0.047968 -0.00176359 0.0193514 -0.0509334 0.998513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.476 -0.0373222 9.6115 399.852 0.725514 100.001 +EDGE_SE3:QUAT 2461 2462 0.552157 -0.0370837 -0.040271 0.00598453 0.00199471 -0.0806481 0.996723 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.995 0.00085226 1.28048 399.987 -1.76483 99.3644 +EDGE_SE3:QUAT 2462 2463 0.640671 -0.150453 -0.147889 0.000730947 0.0110064 -0.0407687 0.999108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.158 -0.00811182 5.51517 399.952 -0.129528 99.9189 +EDGE_SE3:QUAT 2463 2464 0.488227 -0.0813165 0.0287417 0.00624646 0.0017405 -0.0573916 0.998331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.991 0.00106569 1.08252 399.987 -1.85486 99.6853 +EDGE_SE3:QUAT 2464 2465 0.462276 -0.310046 0.109169 -0.000524134 -0.000560236 -0.0666428 0.997777 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 -9.71919e-06 -0.299926 400 0.149855 99.5562 +EDGE_SE3:QUAT 2465 2466 0.634099 -0.0424202 0.10411 -0.00167164 0.00125339 -0.0466422 0.998909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.001 -0.000297299 0.578724 399.999 0.513387 99.7843 +EDGE_SE3:QUAT 2466 2467 0.528947 0.104114 0.109304 0.00380392 0.00656705 -0.101751 0.994781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.058 -0.00602751 3.48497 399.978 -1.00801 99.0018 +EDGE_SE3:QUAT 2467 2468 0.420666 -0.280616 -0.1888 0.00339312 0.00166761 -0.0447329 0.998992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 0.000398352 0.923318 399.995 -1.00331 99.8056 +EDGE_SE3:QUAT 2468 2469 0.496087 0.0813272 0.0606169 0.00207104 0.00978516 -0.0812992 0.99664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.126 -0.0123025 4.96601 399.961 -0.461882 99.4086 +EDGE_SE3:QUAT 2469 2470 0.432009 -0.218489 -0.223036 0.000325054 0.0067596 -0.0842773 0.996419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.059 -0.00669399 3.37514 399.982 0.01706 99.3216 +EDGE_SE3:QUAT 2470 2471 0.377241 -0.158585 0.125795 0.0092149 0.0115919 -0.0958074 0.99529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.174 -0.0145149 6.27947 399.919 -2.54375 99.2129 +EDGE_SE3:QUAT 2471 2472 0.399956 -0.036309 -0.053913 -0.00208243 0.00603898 -0.0677825 0.99768 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.042 -0.00539042 2.92277 399.985 0.707356 99.5662 +EDGE_SE3:QUAT 2472 2473 0.419197 0.035327 0.281385 0.00569891 0.00329994 -0.059225 0.998223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.005 0.000834807 1.84708 399.986 -1.67136 99.668 +EDGE_SE3:QUAT 2473 2474 0.344422 -0.276317 -0.0452232 0.00521126 -0.0040956 -0.0531047 0.998567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.007 -0.00321142 -1.87675 399.986 -1.60764 99.7365 +EDGE_SE3:QUAT 2474 2475 0.530678 -0.278126 -0.0250559 0.000359609 0.000843652 -0.0479358 0.99885 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.001 -3.24188e-05 0.43129 400 -0.0998169 99.7708 +EDGE_SE3:QUAT 2475 2476 0.461974 0.0619353 -0.0616054 0.00635243 0.0105023 -0.026719 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.133 0.0014229 5.35156 399.943 -1.8493 100.02 +EDGE_SE3:QUAT 2476 2477 0.299422 -0.0292875 -0.0874556 -0.00191739 0.00106489 -0.0833322 0.996519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.999 -0.000259239 0.43347 399.999 0.593739 99.3073 +EDGE_SE3:QUAT 2477 2478 0.452342 0.0281974 -0.0173345 0.0016848 0.00522895 -0.0648302 0.997881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.036 -0.00239986 2.6703 399.988 -0.437696 99.6002 +EDGE_SE3:QUAT 2478 2479 0.618512 -0.0966368 0.15368 0.00809059 0.00128859 -0.0736657 0.997249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.979 0.00150889 0.998076 399.979 -2.41015 99.4793 +EDGE_SE3:QUAT 2479 2480 0.435326 -0.200552 -0.0933764 0.00160756 0.00743758 -0.0552882 0.998441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.073 -0.00439936 3.76258 399.977 -0.400012 99.7344 +EDGE_SE3:QUAT 2480 2481 0.488551 -0.179534 -0.0753795 -0.00232752 0.00166291 -0.048572 0.998816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.001 -0.000540161 0.761916 399.997 0.714716 99.7674 +EDGE_SE3:QUAT 2481 2482 0.368743 -0.169351 -0.064621 -0.00301519 -0.00503854 -0.0509059 0.998686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.032 -0.000863015 -2.60564 399.987 0.853468 99.7622 +EDGE_SE3:QUAT 2482 2483 0.424954 0.0182101 0.0646437 0.00557562 -0.00332871 -0.0481854 0.998817 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.999 -0.0023496 -1.4998 399.987 -1.70541 99.7839 +EDGE_SE3:QUAT 2483 2484 0.352777 -0.167919 0.0639258 0.00144043 0.00823462 -0.0541219 0.998499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.089 -0.00550441 4.15419 399.972 -0.342949 99.7557 +EDGE_SE3:QUAT 2484 2485 0.394039 0.0109916 0.133616 0.00109027 0.00125444 -0.066572 0.99778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.002 -5.94907e-05 0.668206 399.999 -0.310543 99.5584 +EDGE_SE3:QUAT 2485 2486 0.170097 -0.0569364 0.133644 0.00161142 0.000510701 -0.105911 0.994374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400 4.55189e-05 0.354792 399.999 -0.47336 98.8794 +EDGE_SE3:QUAT 2486 2487 0.291923 -0.350715 -0.0506407 0.0109068 0.00354569 -0.0305342 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.973 0.00375415 1.97103 399.959 -3.25056 99.9527 +EDGE_SE3:QUAT 2487 2488 0.311796 -0.0618708 -0.0102698 0.00453058 0.010831 -0.0739562 0.997192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.155 -0.011339 5.59194 399.947 -1.19915 99.545 +EDGE_SE3:QUAT 2488 2489 0.413104 -0.13094 -0.140749 0.000111483 0.00819268 -0.0652255 0.997837 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.086 -0.00775251 4.08597 399.974 0.0737738 99.6213 +EDGE_SE3:QUAT 2489 2490 0.379747 -0.177883 0.0447272 0.00103765 0.0084587 -0.0367211 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.093 -0.00387995 4.24814 399.971 -0.249159 99.9158 +EDGE_SE3:QUAT 2490 2491 0.354395 -0.0230735 -0.0789061 0.00807519 0.016532 -0.0936027 0.99544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.366 -0.0354889 8.66207 399.871 -2.11321 99.3473 +EDGE_SE3:QUAT 2491 2492 0.166564 -0.170059 0.0495732 0.00678506 -0.00485559 -0.059416 0.998198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.005 -0.00481321 -2.17851 399.978 -2.09445 99.675 +EDGE_SE3:QUAT 2492 2493 0.293104 -0.104138 -0.110184 -0.00374684 -0.000126996 -0.034529 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.994 0.000140051 -0.141023 399.996 1.12339 99.885 +EDGE_SE3:QUAT 2493 2494 0.286681 0.0800986 -0.140534 -0.00579661 0.00107803 -0.0675768 0.997697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.987 -0.000219164 0.302117 399.99 1.7549 99.5538 +EDGE_SE3:QUAT 2494 2495 0.451006 0.0159923 -0.110392 -0.00604367 0.00641153 -0.060747 0.998114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.03 -0.00735166 2.97534 399.974 1.89216 99.6678 +EDGE_SE3:QUAT 2495 2496 0.407636 -0.207573 -0.132776 -0.00107264 -0.00397547 -0.0424757 0.999089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.021 -0.000799366 -2.01194 399.993 0.288049 99.8312 +EDGE_SE3:QUAT 2496 2497 0.339458 -0.0490249 -0.183052 0.00643453 0.00175024 -0.0607971 0.998128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.99 0.00111116 1.10663 399.986 -1.91011 99.6459 +EDGE_SE3:QUAT 2497 2498 0.182255 -0.232472 -0.0869942 0.00581051 0.00345223 -0.0467387 0.998884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.005 0.00114127 1.8856 399.985 -1.71136 99.8012 +EDGE_SE3:QUAT 2498 2499 0.277322 -0.0641475 0.0477913 -0.00140515 0.000496405 -0.0715811 0.997434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.999 -6.02683e-05 0.186812 399.999 0.429041 99.4883 +EDGE_SE3:QUAT 0 50 0.123684 -3.04765 -0.0287081 0.0262351 -0.00714894 -0.0422944 0.998735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 -0.0155759 -2.90153 399.776 -7.93 100.055 +EDGE_SE3:QUAT 1 51 -0.119112 -3.01805 -0.0691574 0.0312538 -0.00586279 -0.040196 0.998686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 -0.0118777 -2.17151 399.696 -9.42079 100.148 +EDGE_SE3:QUAT 2 52 -0.245056 -2.86505 -0.129966 0.0370929 0.000988243 -0.00197917 0.999309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.451 0.00419594 0.537538 399.587 -11.1198 100.413 +EDGE_SE3:QUAT 3 53 -0.0837652 -3.07691 -0.138081 0.0298998 -0.00342952 -0.00401799 0.999539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00960027 -1.64136 399.727 -8.96845 100.274 +EDGE_SE3:QUAT 4 54 -0.0711695 -2.97051 -0.100013 0.0309442 0.00508683 -0.00349862 0.999502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.653 0.0162264 2.60638 399.702 -9.27465 100.305 +EDGE_SE3:QUAT 5 55 0.100612 -3.03312 -0.090605 0.0233198 0.00284331 0.00729108 0.999697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 0.00592456 1.31893 399.834 -6.99811 100.163 +EDGE_SE3:QUAT 6 56 0.0371277 -3.07963 -0.176527 0.0311826 0.00356877 -0.024848 0.999198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.0150728 2.24667 399.702 -9.33299 100.243 +EDGE_SE3:QUAT 7 57 0.104692 -3.09555 -0.120551 0.0356209 0.00131676 0.029972 0.998915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 -0.00292595 0.0169786 399.619 -10.689 100.291 +EDGE_SE3:QUAT 8 58 0.00719936 -3.14389 -0.027828 0.031252 0.00102183 -0.0221905 0.999265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 0.00739354 0.926147 399.706 -9.36717 100.246 +EDGE_SE3:QUAT 9 59 0.0926379 -3.00401 -0.0471469 0.0312054 -5.72382e-05 0.00978124 0.999465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 -0.00207965 -0.211663 399.708 -9.3571 100.283 +EDGE_SE3:QUAT 10 60 0.0708412 -3.06927 -0.0337878 0.0308573 0.00131811 -0.00666778 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.00530056 0.781881 399.714 -9.25105 100.283 +EDGE_SE3:QUAT 11 61 0.154444 -3.02448 -0.160338 0.0285017 0.000764256 0.0489922 0.998392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 -0.00573874 -0.455899 399.756 -8.55793 100.004 +EDGE_SE3:QUAT 12 62 0.178067 -3.03583 -0.146661 0.033323 -0.00224585 -0.0153505 0.999324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.559 -0.00413764 -0.81479 399.665 -9.99856 100.312 +EDGE_SE3:QUAT 13 63 0.113612 -3.13653 0.00541842 0.0211283 0.00373656 0.0471236 0.998659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 0.00426057 1.26695 399.862 -6.37457 99.9179 +EDGE_SE3:QUAT 14 64 -0.191278 -3.10587 -0.315564 0.0395874 -0.00574735 -0.00818096 0.999166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.409 -0.0205684 -2.67548 399.517 -11.8756 100.484 +EDGE_SE3:QUAT 15 65 -0.0746119 -3.10285 -0.027189 0.0336099 -0.00662807 -0.00342223 0.999407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 -0.0217486 -3.24211 399.644 -10.0808 100.368 +EDGE_SE3:QUAT 16 66 0.00767487 -2.90585 -0.0636412 0.0338482 0.00040386 0.0269516 0.999063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.542 -0.004793 -0.345427 399.656 -10.152 100.271 +EDGE_SE3:QUAT 17 67 0.0348257 -3.07488 0.0865152 0.0278889 -0.0168201 -0.0188729 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.024 -0.0533016 -8.09281 399.657 -8.4217 100.385 +EDGE_SE3:QUAT 18 68 0.034272 -2.9771 -0.0275615 0.0297532 -0.00407008 -0.0113089 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.0103701 -1.83144 399.728 -8.9311 100.263 +EDGE_SE3:QUAT 19 69 0.0414539 -2.94622 -0.147426 0.0169493 0.00152461 0.02986 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.886 0.000915985 0.45795 399.913 -5.09391 99.9979 +EDGE_SE3:QUAT 20 70 -0.0269102 -2.79063 -0.0848862 0.0350028 0.000701303 -0.0111867 0.999324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.512 0.00516268 0.585062 399.632 -10.493 100.356 +EDGE_SE3:QUAT 21 71 -0.0671743 -3.07386 -0.0497795 0.0206745 0.00195991 0.0117681 0.999715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.832 0.00310345 0.83351 399.87 -6.20575 100.117 +EDGE_SE3:QUAT 22 72 -0.0362474 -3.05248 -0.160313 0.0274248 0.00343805 0.00157422 0.999617 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.00921447 1.69203 399.77 -8.22518 100.233 +EDGE_SE3:QUAT 23 73 0.119773 -3.09523 -0.13553 0.0356979 0.00728375 0.0388232 0.998582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.526 0.0183561 2.80216 399.6 -10.7609 100.258 +EDGE_SE3:QUAT 24 74 0.14435 -2.94311 -0.0670919 0.0275082 0.00428261 0.00752252 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 0.0108539 2.01572 399.766 -8.25553 100.233 +EDGE_SE3:QUAT 25 75 0.0212556 -3.1875 -0.154731 0.030008 -0.00454567 0.0076988 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 -0.0146955 -2.40965 399.721 -8.99093 100.28 +EDGE_SE3:QUAT 26 76 0.0657844 -3.08702 -0.00356366 0.0275256 0.003594 0.0181604 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 0.00743044 1.49546 399.768 -8.26785 100.201 +EDGE_SE3:QUAT 27 77 -0.0102091 -2.86533 0.139962 0.0158568 0.000580745 -0.0233131 0.999602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.901 0.00205186 0.511911 399.924 -4.75416 100.022 +EDGE_SE3:QUAT 28 78 -0.116977 -3.13993 -0.0097921 0.0304685 0.00194051 0.0190815 0.999352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 0.00241717 0.620447 399.72 -9.14424 100.244 +EDGE_SE3:QUAT 29 79 -0.0591044 -3.10293 -0.164402 0.0388677 -0.00706399 -0.00777936 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.453 -0.0257015 -3.34616 399.528 -11.6613 100.48 +EDGE_SE3:QUAT 30 80 -0.192369 -3.0277 0.0384235 0.0341352 -0.00478582 -0.0104404 0.999351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 -0.0142389 -2.17655 399.642 -10.2443 100.353 +EDGE_SE3:QUAT 31 81 -0.0590693 -3.17731 -0.0370921 0.0389039 -0.000872266 -0.0213428 0.999015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.394 0.00307414 0.0625034 399.546 -11.6669 100.409 +EDGE_SE3:QUAT 32 82 0.0104447 -2.95858 -0.123556 0.0325847 0.00487065 -0.00963106 0.999411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.0174275 2.62129 399.671 -9.76033 100.328 +EDGE_SE3:QUAT 33 83 -0.166851 -3.00612 -0.0390378 0.0289383 0.00503153 -0.0135132 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 0.0160908 2.74832 399.738 -8.66387 100.253 +EDGE_SE3:QUAT 34 84 -0.0838249 -2.94966 -0.159055 0.0294205 0.00635398 -0.0349129 0.998937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.731 0.0212329 3.78779 399.721 -8.7785 100.175 +EDGE_SE3:QUAT 35 85 -0.0330709 -3.08556 -0.027849 0.0375211 -0.00545126 -0.0135511 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.466 -0.0171802 -2.41698 399.567 -11.2628 100.422 +EDGE_SE3:QUAT 36 86 0.0352295 -3.03801 -0.120413 0.0297732 -0.00121899 -0.0161638 0.999425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 -0.00077165 -0.320226 399.734 -8.93232 100.24 +EDGE_SE3:QUAT 37 87 0.0288712 -3.21631 0.0677728 0.0322064 0.0086392 0.0354216 0.998816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.649 0.0239155 3.62723 399.663 -9.71885 100.227 +EDGE_SE3:QUAT 38 88 -0.0353526 -2.88279 -0.148361 0.0378015 0.0012261 0.0188749 0.999106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.428 -0.000763634 0.184222 399.571 -11.3377 100.393 +EDGE_SE3:QUAT 39 89 -0.00830657 -3.0073 0.00305971 0.0184541 -0.00605127 -0.0168982 0.999669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.905 -0.0110105 -2.83716 399.884 -5.55554 100.097 +EDGE_SE3:QUAT 40 90 0.0777223 -2.85121 0.0761198 0.0321415 0.00630446 0.0183762 0.999294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 0.0175007 2.79438 399.676 -9.6604 100.3 +EDGE_SE3:QUAT 41 91 0.021105 -3.00492 -0.133593 0.0329977 -0.00185146 -0.0233368 0.999181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.565 -0.00105669 -0.462581 399.672 -9.90345 100.273 +EDGE_SE3:QUAT 42 92 -0.089812 -3.01466 -0.287607 0.0307 -0.00142756 0.00675158 0.999505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 -0.0056136 -0.837476 399.716 -9.20374 100.28 +EDGE_SE3:QUAT 43 93 0.130522 -3.11783 -0.311142 0.0217974 0.00326883 -0.014443 0.999653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 0.00815454 1.82235 399.853 -6.52823 100.13 +EDGE_SE3:QUAT 44 94 -0.0979209 -2.95504 -0.0934092 0.0257813 -0.00137525 0.0304377 0.999203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 -0.00731295 -1.15725 399.799 -7.72452 100.11 +EDGE_SE3:QUAT 45 95 -0.0384673 -3.09158 -0.00400611 0.0381852 -0.00620336 -0.00251269 0.999248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.464 -0.0230869 -3.04044 399.547 -11.4493 100.463 +EDGE_SE3:QUAT 46 96 0.107757 -2.94807 -0.0544414 0.030788 -0.000206677 -0.012414 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 0.00171638 0.126 399.716 -9.23278 100.269 +EDGE_SE3:QUAT 47 97 0.191799 -2.98088 -0.114885 0.0288337 -0.0100169 0.010598 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 -0.0286734 -5.1895 399.709 -8.62317 100.312 +EDGE_SE3:QUAT 48 98 -0.114557 -2.90895 -0.336941 0.0316 0.00461329 0.00221936 0.999487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 0.0141991 2.26266 399.692 -9.47684 100.314 +EDGE_SE3:QUAT 49 99 0.0447448 -3.17938 -0.0524665 0.0183332 0.0131246 0.0269305 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.066 0.0300313 6.26315 399.833 -5.56811 100.141 +EDGE_SE3:QUAT 50 100 0.294107 -2.97696 0.0372275 0.0261566 0.00449078 -0.00478798 0.999636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 0.0122105 2.31927 399.786 -7.83962 100.218 +EDGE_SE3:QUAT 51 101 -0.0215351 -3.05915 -0.14967 0.028995 -0.000914519 0.0146438 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 -0.00505841 -0.711501 399.747 -8.69243 100.232 +EDGE_SE3:QUAT 52 102 -0.173278 -3.06042 0.177547 0.031143 0.000802715 0.00631632 0.999495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.00127428 0.283007 399.709 -9.33943 100.287 +EDGE_SE3:QUAT 53 103 -0.00268539 -3.08559 -0.202858 0.0263648 0.00475648 -0.0202183 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 0.0143091 2.6959 399.781 -7.88743 100.187 +EDGE_SE3:QUAT 54 104 0.0433166 -3.06641 -0.116031 0.0234529 -0.00469472 0.0244823 0.999414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.0124541 -2.68962 399.825 -7.01115 100.124 +EDGE_SE3:QUAT 55 105 0.0259222 -2.88869 0.00719153 0.0280146 0.0033886 -0.0106421 0.999545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 0.0108888 1.87186 399.76 -8.39375 100.233 +EDGE_SE3:QUAT 56 106 -0.0785152 -3.13599 -0.180788 0.0313766 0.00336467 -0.0183513 0.999333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.0136276 2.0258 399.699 -9.39616 100.272 +EDGE_SE3:QUAT 57 107 -0.0441094 -2.91311 -0.116708 0.0312349 0.00216473 0.0106 0.999454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.613 0.00474304 0.882732 399.706 -9.37057 100.284 +EDGE_SE3:QUAT 58 108 0.0230801 -2.97504 -0.357061 0.0335847 -0.00412044 0.0125095 0.999349 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 -0.0161671 -2.31 399.654 -10.0592 100.337 +EDGE_SE3:QUAT 59 109 -0.00305562 -3.12308 -0.287325 0.0285105 0.00248796 0.0158892 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 0.00461256 0.971084 399.754 -8.55787 100.222 +EDGE_SE3:QUAT 60 110 -0.025776 -2.93824 -0.0518619 0.0293377 -0.00377868 -0.00155865 0.999561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.674 -0.0108432 -1.86053 399.736 -8.79839 100.268 +EDGE_SE3:QUAT 61 111 -0.0288368 -3.12871 -0.17189 0.0343147 0.00390243 -0.022249 0.999156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.0177097 2.40634 399.639 -10.2712 100.318 +EDGE_SE3:QUAT 62 112 -0.129161 -3.26124 -0.190558 0.0265101 -0.00703106 -0.0214177 0.999394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 -0.0172056 -3.1717 399.771 -7.98014 100.195 +EDGE_SE3:QUAT 63 113 0.0883249 -3.13239 -0.04713 0.0287498 0.00643024 0.0430673 0.998638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.697 0.0133158 2.46524 399.738 -8.67894 100.083 +EDGE_SE3:QUAT 64 114 0.0154263 -3.12403 -0.0570956 0.0271265 -0.00624743 0.0415748 0.998748 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.784 -0.0188915 -3.79381 399.761 -8.08418 100.085 +EDGE_SE3:QUAT 65 115 0.184162 -3.0453 -0.118383 0.0225675 0.00276275 0.0144555 0.999637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 0.00490715 1.18481 399.844 -6.77665 100.136 +EDGE_SE3:QUAT 66 116 0.0749906 -3.08305 -0.135897 0.0363999 0.000473092 0.0033828 0.999331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 0.000822357 0.162414 399.602 -10.9131 100.396 +EDGE_SE3:QUAT 67 117 -0.0305342 -3.10432 0.00537417 0.0292679 0.00476839 0.0292938 0.999131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.674 0.00968436 1.86645 399.735 -8.8055 100.183 +EDGE_SE3:QUAT 68 118 -0.0387159 -3.01347 -0.108519 0.0221468 -0.00160987 -0.0061728 0.999734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 -0.00298032 -0.722548 399.852 -6.6444 100.145 +EDGE_SE3:QUAT 69 119 -0.0875281 -2.96544 -0.0468108 0.0299696 -0.00350606 0.0174634 0.999392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.664 -0.0131083 -2.06517 399.725 -8.97468 100.25 +EDGE_SE3:QUAT 70 120 -0.0501515 -3.09343 -0.0300745 0.0321299 -0.012218 -0.0327572 0.998872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.736 -0.0397494 -5.46831 399.636 -9.71277 100.292 +EDGE_SE3:QUAT 71 121 0.00551799 -3.1507 -0.223002 0.0353998 -0.00871546 -0.00703536 0.99931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0299937 -4.20425 399.595 -10.6237 100.422 +EDGE_SE3:QUAT 72 122 0.0597231 -3.08063 -0.127074 0.0339776 -0.00787051 -0.01874 0.999216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.601 -0.0241287 -3.54861 399.631 -10.2162 100.349 +EDGE_SE3:QUAT 73 123 0.0273583 -3.01523 -0.0374404 0.0361071 -0.00467231 -0.0266893 0.998981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 -0.0104957 -1.75414 399.602 -10.8509 100.33 +EDGE_SE3:QUAT 74 124 -0.140182 -2.86662 -0.0667824 0.0287741 0.00199134 0.0173095 0.999434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.00291938 0.695934 399.75 -8.63592 100.22 +EDGE_SE3:QUAT 75 125 0.149265 -3.11637 0.114881 0.0316619 -0.00227682 -0.010626 0.99944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 -0.0051348 -0.935487 399.697 -9.49874 100.292 +EDGE_SE3:QUAT 76 126 0.0649766 -3.13012 0.115222 0.0310342 -0.00457884 -0.0262702 0.999163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 -0.00976442 -1.79717 399.704 -9.3306 100.231 +EDGE_SE3:QUAT 77 127 -0.0452628 -2.9625 -0.119995 0.0368195 -0.000523249 -0.0333564 0.998765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 0.00708026 0.47525 399.593 -11.0439 100.296 +EDGE_SE3:QUAT 78 128 -0.0235386 -3.20664 -0.00789819 0.028545 -0.00555896 0.0123939 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0170948 -2.98966 399.742 -8.54571 100.253 +EDGE_SE3:QUAT 79 129 0.0433156 -2.9881 0.0160618 0.0296462 0.00101355 -0.0017554 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.65 0.00330446 0.537591 399.736 -8.88958 100.264 +EDGE_SE3:QUAT 80 130 -0.190593 -3.07302 0.0165346 0.0293419 -0.00604467 0.00137341 0.99955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.0178757 -3.04456 399.727 -8.79632 100.284 +EDGE_SE3:QUAT 81 131 -0.0259444 -2.8563 -0.0218777 0.0227683 -0.00686702 0.0227125 0.999459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.867 -0.0157483 -3.74128 399.824 -6.79719 100.141 +EDGE_SE3:QUAT 82 132 -0.103071 -2.91015 -0.16109 0.0318458 0.0023001 -0.0157771 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.0102802 1.45013 399.693 -9.54185 100.285 +EDGE_SE3:QUAT 83 133 -0.0731008 -3.07324 -0.165711 0.029624 -0.00251336 0.0194216 0.999369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.0104972 -1.6004 399.734 -8.87387 100.232 +EDGE_SE3:QUAT 84 134 -0.107305 -3.25517 0.0327166 0.0345157 -0.00302448 0.00915263 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 -0.0124116 -1.70005 399.639 -10.3429 100.357 +EDGE_SE3:QUAT 85 135 -0.0838882 -3.19586 -0.207621 0.0344823 0.0068423 -0.0105914 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 0.0251051 3.6369 399.624 -10.3229 100.381 +EDGE_SE3:QUAT 86 136 0.0157613 -2.92032 -0.0431684 0.032139 -0.00279256 0.00931315 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.0107198 -1.57446 399.687 -9.63143 100.308 +EDGE_SE3:QUAT 87 137 0.00197004 -3.03679 0.0128745 0.0274841 -0.0114001 -0.0220213 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.842 -0.0326409 -5.33261 399.724 -8.29055 100.261 +EDGE_SE3:QUAT 88 138 -0.12332 -3.08132 -0.0995277 0.0353843 -0.00418229 -0.00416156 0.999356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.52 -0.0138497 -2.00055 399.618 -10.6117 100.385 +EDGE_SE3:QUAT 89 139 -0.00275223 -3.19583 -0.0819252 0.026525 -0.00310123 -0.0283002 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 -0.0044938 -1.09835 399.786 -7.97321 100.135 +EDGE_SE3:QUAT 90 140 0.104303 -3.11898 -0.266343 0.0322625 0.00598984 0.036831 0.998783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 0.013066 2.27616 399.676 -9.71951 100.194 +EDGE_SE3:QUAT 91 141 -0.024415 -2.83466 -0.257886 0.0356727 -0.00449634 -0.0120898 0.99928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 -0.0132826 -1.98675 399.611 -10.7057 100.379 +EDGE_SE3:QUAT 92 142 -0.0307797 -2.98277 0.074437 0.0306307 -0.013226 0.0192179 0.999258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.88 -0.0376952 -6.96327 399.646 -9.13034 100.376 +EDGE_SE3:QUAT 93 143 -0.0211845 -3.16763 -0.127323 0.036904 -0.00588465 0.0117208 0.999233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.51 -0.0240312 -3.19825 399.577 -11.049 100.422 +EDGE_SE3:QUAT 94 144 0.108172 -3.12806 -0.223934 0.0296979 -0.00164592 -0.0482099 0.998394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 0.00363262 0.0375378 399.734 -8.92477 100.033 +EDGE_SE3:QUAT 95 145 0.0559591 -2.82278 -0.0672094 0.0311519 0.00205808 0.000343586 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 0.0063358 1.02173 399.707 -9.34108 100.294 +EDGE_SE3:QUAT 96 146 0.000928069 -3.04331 0.00953992 0.0259038 -0.0020335 0.0367162 0.998988 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 -0.00956345 -1.58525 399.796 -7.75513 100.072 +EDGE_SE3:QUAT 97 147 0.0309534 -2.97941 -0.114619 0.027857 0.00851342 -0.00965075 0.999529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 0.023901 4.41589 399.737 -8.33594 100.277 +EDGE_SE3:QUAT 98 148 -0.193633 -3.07722 -0.0303492 0.0369517 -0.00586502 -0.00437134 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 -0.0206996 -2.83229 399.577 -11.0822 100.431 +EDGE_SE3:QUAT 99 149 -0.0268638 -3.02365 -0.11236 0.0408092 -0.00128584 0.00872075 0.999128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.338 -0.00808879 -0.85533 399.499 -12.2304 100.494 +EDGE_SE3:QUAT 100 150 -0.091195 -3.10917 -0.131026 0.0292275 0.00163261 -0.0386898 0.998822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.0107997 1.49259 399.741 -8.75386 100.112 +EDGE_SE3:QUAT 101 151 -0.184789 -3.14272 -0.235034 0.0294978 -0.00105367 0.0440123 0.998595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.0102769 -1.30378 399.737 -8.83889 100.071 +EDGE_SE3:QUAT 102 152 -0.0763466 -3.00259 -0.111874 0.0399851 -0.0070261 0.0108798 0.999116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.436 -0.0304429 -3.7693 399.499 -11.9692 100.506 +EDGE_SE3:QUAT 103 153 0.0438277 -2.96722 0.0459768 0.0332768 0.00170952 0.014554 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.00249028 0.563287 399.667 -9.9828 100.312 +EDGE_SE3:QUAT 104 154 -0.0624419 -3.03437 -0.157666 0.0237789 -8.47801e-05 0.0169676 0.999573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.774 -0.00211132 -0.284372 399.83 -7.13171 100.141 +EDGE_SE3:QUAT 105 155 0.117743 -2.83783 -0.167352 0.0311918 -0.00397138 -0.000134197 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 -0.0123484 -1.98155 399.702 -9.35272 100.303 +EDGE_SE3:QUAT 106 156 0.0449871 -3.06183 -0.169848 0.0331738 -0.00346115 -0.0345042 0.998848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.564 -0.00415829 -1.04075 399.666 -9.97241 100.216 +EDGE_SE3:QUAT 107 157 -0.0960327 -3.08018 -0.160623 0.0326278 -0.00463288 -0.00873411 0.999419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 -0.0135275 -2.14327 399.673 -9.79089 100.325 +EDGE_SE3:QUAT 108 158 0.104944 -3.01454 -0.0810527 0.0279271 0.000381206 0.00824553 0.999576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.688 -0.000222559 0.0523323 399.766 -8.37559 100.227 +EDGE_SE3:QUAT 109 159 0.019539 -2.96727 -0.106413 0.028227 -0.000192605 0.00591056 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 -0.00148279 -0.196305 399.761 -8.46455 100.236 +EDGE_SE3:QUAT 110 160 -0.00660569 -3.09514 -0.054324 0.0329591 -0.000125299 0.0416167 0.99859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 -0.00925545 -0.884723 399.673 -9.8841 100.154 +EDGE_SE3:QUAT 111 161 -0.175793 -3.09713 -0.0226281 0.0256573 -0.00444058 -0.0131883 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.0100405 -2.01576 399.795 -7.70628 100.192 +EDGE_SE3:QUAT 112 162 0.0302867 -2.89947 0.0285285 0.0326617 2.97582e-05 -0.0114648 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 0.00253788 0.239449 399.68 -9.79342 100.307 +EDGE_SE3:QUAT 113 163 -0.0432065 -3.1782 -0.150945 0.0358117 -0.00476288 0.0424094 0.998447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.547 -0.0247676 -3.28578 399.603 -10.6983 100.231 +EDGE_SE3:QUAT 114 164 -0.00322512 -3.02308 0.0908843 0.043245 0.00280514 -0.00557412 0.999045 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.265 0.0140787 1.54477 399.436 -12.958 100.564 +EDGE_SE3:QUAT 115 165 0.0180775 -3.05186 -0.186293 0.0341784 -0.00324975 -0.020722 0.999196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 -0.00646881 -1.19783 399.646 -10.2616 100.313 +EDGE_SE3:QUAT 116 166 -0.0975132 -3.20295 -0.17434 0.0302428 0.0011499 0.00957349 0.999496 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 0.00173258 0.400769 399.725 -9.07102 100.266 +EDGE_SE3:QUAT 117 167 0.0654124 -2.96418 -0.217887 0.0317058 -0.00290588 0.0103463 0.999439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 -0.0110794 -1.64831 399.695 -9.50087 100.298 +EDGE_SE3:QUAT 118 168 0.100361 -3.04344 -0.158514 0.021619 0.00613292 -0.0018191 0.999746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.863 0.0133109 3.08917 399.845 -6.48135 100.166 +EDGE_SE3:QUAT 119 169 0.180965 -3.16839 0.0125299 0.0365619 -0.000521283 -0.0258896 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.466 0.00500597 0.307393 399.599 -10.9651 100.334 +EDGE_SE3:QUAT 120 170 0.0746068 -3.01461 -0.18407 0.0294273 -0.00904285 -0.00371181 0.999519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.756 -0.0265324 -4.45354 399.708 -8.82933 100.314 +EDGE_SE3:QUAT 121 171 0.0109993 -3.01379 -0.102388 0.0286589 0.00137568 0.00907061 0.999547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.00246599 0.531355 399.753 -8.59673 100.239 +EDGE_SE3:QUAT 122 172 -0.111558 -2.94293 -0.195782 0.0340554 -0.00077982 -0.0107058 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.536 -0.000170261 -0.170802 399.652 -10.2126 100.337 +EDGE_SE3:QUAT 123 173 0.0800822 -3.3112 -0.124141 0.0338539 -0.00487823 -0.0385965 0.998669 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.553 -0.00844294 -1.65005 399.649 -10.1903 100.205 +EDGE_SE3:QUAT 124 174 -0.0792538 -3.01441 0.00500951 0.0302185 0.00406264 -0.0300499 0.999083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.0163698 2.5728 399.718 -9.03778 100.2 +EDGE_SE3:QUAT 125 175 0.0662933 -2.99194 -0.286008 0.0391835 -0.00450532 0.0140746 0.999123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.422 -0.0212761 -2.58013 399.53 -11.733 100.458 +EDGE_SE3:QUAT 126 176 -0.0173762 -3.1868 -0.0394693 0.0299306 0.0025715 -0.0131792 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 0.00983185 1.52116 399.728 -8.96844 100.257 +EDGE_SE3:QUAT 127 177 -0.0569387 -2.96806 -0.200005 0.0220657 0.00734787 0.0161407 0.999599 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.866 0.016057 3.45836 399.833 -6.64129 100.155 +EDGE_SE3:QUAT 128 178 -0.0739367 -3.07313 -0.0364267 0.0357726 -0.0124009 0.0278892 0.998894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.733 -0.0425769 -6.79199 399.55 -10.6524 100.429 +EDGE_SE3:QUAT 129 179 0.0334896 -3.08379 -0.165323 0.0287371 0.00365248 0.0228749 0.999319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 0.00705443 1.42981 399.748 -8.63484 100.202 +EDGE_SE3:QUAT 130 180 0.0600659 -3.04662 -0.232627 0.0267125 -0.000283255 0.00431984 0.999634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 -0.00137053 -0.210753 399.786 -8.01066 100.212 +EDGE_SE3:QUAT 131 181 -0.0705189 -3.08063 -0.0281943 0.0254722 0.00692166 0.00982113 0.999603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.797 0.0171418 3.30893 399.787 -7.65205 100.216 +EDGE_SE3:QUAT 132 182 0.137935 -3.01711 -0.24742 0.0319121 -0.0079227 -0.00731089 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 -0.0245693 -3.81834 399.67 -9.57901 100.342 +EDGE_SE3:QUAT 133 183 0.113449 -3.24191 -0.0118171 0.028893 0.00776978 0.0377226 0.99884 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 0.0190505 3.22388 399.728 -8.72405 100.141 +EDGE_SE3:QUAT 134 184 -0.00249721 -3.08846 -0.119883 0.0289037 -0.00236693 -0.00321582 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 -0.00632368 -1.12683 399.747 -8.66891 100.253 +EDGE_SE3:QUAT 135 185 0.00297203 -3.10605 0.158867 0.0363486 0.00175432 -0.00870531 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.478 0.0085907 1.06585 399.602 -10.8943 100.392 +EDGE_SE3:QUAT 136 186 0.0484651 -2.93186 -0.241964 0.0303533 -0.00127655 -0.0286876 0.999127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 0.00141383 -0.115119 399.723 -9.11036 100.195 +EDGE_SE3:QUAT 137 187 0.0697683 -3.12328 -0.185728 0.0407179 -0.00184925 -0.035074 0.998553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.336 0.00412031 -0.0661589 399.501 -12.2207 100.375 +EDGE_SE3:QUAT 138 188 -0.182655 -3.20378 -0.147575 0.0234723 0.000175178 -0.0236059 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.781 0.00298551 0.419831 399.835 -7.03957 100.11 +EDGE_SE3:QUAT 139 189 -0.0892435 -2.88768 -0.0776466 0.0271202 0.00120513 -0.0351331 0.999014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.00811138 1.17284 399.778 -8.12616 100.1 +EDGE_SE3:QUAT 140 190 -0.0090601 -3.01519 -0.0517473 0.0291218 -0.00193417 0.0603758 0.997749 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 -0.0142533 -2.01671 399.742 -8.71434 99.899 +EDGE_SE3:QUAT 141 191 0.00510901 -2.98367 -0.207731 0.0308954 -0.00657332 -0.00104298 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.0201836 -3.26499 399.696 -9.26456 100.316 +EDGE_SE3:QUAT 142 192 0.0666604 -2.89114 -0.0680906 0.0311782 0.00289801 0.0145625 0.999404 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 0.00633918 1.17516 399.705 -9.35756 100.275 +EDGE_SE3:QUAT 143 193 -0.022781 -3.08216 -0.0800965 0.0350168 -0.00236038 -0.0321197 0.998868 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.51 -0.000438964 -0.503456 399.63 -10.5155 100.266 +EDGE_SE3:QUAT 144 194 0.00638825 -3.00042 -0.151838 0.0249313 -0.00271984 0.00727722 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 -0.00756755 -1.46797 399.81 -7.473 100.187 +EDGE_SE3:QUAT 145 195 0.0368719 -2.91428 -0.0857056 0.0293116 0.000146813 0.0219972 0.999328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.00333694 -0.313373 399.742 -8.79105 100.21 +EDGE_SE3:QUAT 146 196 -0.0114202 -3.19583 -0.309015 0.0302992 0.00216347 0.0148387 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.00389378 0.810972 399.723 -9.09227 100.256 +EDGE_SE3:QUAT 147 197 -0.00871662 -3.01961 -0.137155 0.025412 0.000393504 -0.0232665 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.743 0.00395762 0.551154 399.806 -7.61998 100.14 +EDGE_SE3:QUAT 148 198 -0.0677675 -2.98079 -0.0382307 0.0294756 -0.00245402 0.0556247 0.998014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.0150862 -2.20529 399.734 -8.81558 99.9624 +EDGE_SE3:QUAT 149 199 0.0191126 -3.02994 -0.129049 0.0328843 -0.00645109 -0.0331503 0.998888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.598 -0.015647 -2.56577 399.661 -9.90387 100.236 +EDGE_SE3:QUAT 150 200 0.0382134 -3.05662 -0.135943 0.0319954 0.00587123 -0.000452952 0.999471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.018836 2.94196 399.679 -9.59234 100.331 +EDGE_SE3:QUAT 151 201 0.0731876 -3.11192 -0.196398 0.0356986 0.000922517 -0.0114273 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 0.0061573 0.705331 399.617 -10.7008 100.37 +EDGE_SE3:QUAT 152 202 0.130243 -3.0951 -0.054181 0.0288154 -0.0056873 0.0109037 0.999509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.0174809 -3.0301 399.737 -8.62802 100.262 +EDGE_SE3:QUAT 153 203 0.0630173 -2.91525 0.0364883 0.0360011 -0.00464301 -0.00124705 0.99934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.509 -0.0164095 -2.29203 399.603 -10.7939 100.403 +EDGE_SE3:QUAT 154 204 0.161642 -3.15779 0.00582814 0.0283598 0.00276684 0.0126638 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.00592665 1.16682 399.756 -8.51164 100.23 +EDGE_SE3:QUAT 155 205 -0.0757689 -3.06476 -0.0242418 0.0311722 0.00277234 -0.0479523 0.998359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 0.0162729 2.2782 399.703 -9.32358 100.074 +EDGE_SE3:QUAT 156 206 0.102407 -3.05569 -0.172852 0.0384743 0.00616657 -0.00604035 0.999222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.462 0.0250331 3.21894 399.54 -11.5252 100.469 +EDGE_SE3:QUAT 157 207 -0.0809565 -3.10199 0.0555457 0.0263395 0.00787065 0.0204027 0.999414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.788 0.0198494 3.60966 399.769 -7.93072 100.205 +EDGE_SE3:QUAT 158 208 0.102104 -3.09037 -0.0644268 0.0273398 0.00364868 -0.00890552 0.99958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.722 0.0110517 1.96914 399.77 -8.19216 100.227 +EDGE_SE3:QUAT 159 209 -0.0346452 -3.11184 -0.0606164 0.0240126 -0.00212776 0.0198869 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 -0.00714575 -1.34942 399.825 -7.1936 100.138 +EDGE_SE3:QUAT 160 210 0.0286888 -2.96378 -0.17248 0.0182924 0.000887544 -0.0564385 0.998238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.873 0.00498755 1.0611 399.899 -5.47959 99.7843 +EDGE_SE3:QUAT 161 211 -0.142765 -3.17487 -0.190226 0.0180159 -0.00159604 -0.0141209 0.999737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.872 -0.00200088 -0.645032 399.902 -5.40855 100.079 +EDGE_SE3:QUAT 162 212 -0.0016887 -3.03451 -0.0732073 0.0266979 0.000960911 -0.0051307 0.99963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 0.00328164 0.562306 399.786 -8.00554 100.212 +EDGE_SE3:QUAT 163 213 0.0686502 -2.99854 -0.033735 0.0244276 -0.00846693 0.00609077 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.859 -0.0206279 -4.32146 399.792 -7.31448 100.227 +EDGE_SE3:QUAT 164 214 0.00559263 -3.04826 0.110138 0.0388945 -0.00169455 0.0126791 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.402 -0.0102917 -1.14175 399.545 -11.6554 100.441 +EDGE_SE3:QUAT 165 215 -0.079513 -2.93213 -0.228321 0.0321525 0.00112567 -0.00804565 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 0.00524599 0.717441 399.689 -9.63902 100.305 +EDGE_SE3:QUAT 166 216 0.000612582 -3.13253 -0.0272573 0.032612 -0.00434434 -0.00774051 0.999429 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 -0.0127299 -2.01867 399.674 -9.78482 100.325 +EDGE_SE3:QUAT 167 217 0.0263059 -2.91893 -0.272428 0.0292118 0.00868494 -0.0106826 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.766 0.0256644 4.52722 399.713 -8.73965 100.301 +EDGE_SE3:QUAT 168 218 -0.0999359 -2.98392 -0.0647397 0.0327227 0.00116273 -0.00727271 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 0.00532707 0.723522 399.678 -9.8099 100.317 +EDGE_SE3:QUAT 169 219 0.106994 -3.21091 -0.297587 0.0225322 -0.00407363 0.00182039 0.999736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.00930466 -2.06061 399.841 -6.75617 100.164 +EDGE_SE3:QUAT 170 220 0.0292042 -3.14077 -0.131728 0.0244863 0.00259261 0.00285635 0.999693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 0.00603225 1.25366 399.818 -7.34505 100.184 +EDGE_SE3:QUAT 171 221 0.0251717 -3.00265 0.0194363 0.0352656 -0.0114531 0.0036435 0.999306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0405232 -5.79991 399.574 -10.5612 100.465 +EDGE_SE3:QUAT 172 222 -0.134656 -3.05362 0.13276 0.032938 -0.00489244 -0.0020233 0.999443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.596 -0.0157394 -2.40404 399.665 -9.87747 100.341 +EDGE_SE3:QUAT 173 223 -0.062719 -3.15837 -0.0502821 0.0327734 -0.00335771 0.0228681 0.999196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 -0.01518 -2.12605 399.672 -9.81181 100.281 +EDGE_SE3:QUAT 174 224 0.163986 -3.13471 -0.0134047 0.03578 -0.00267189 0.000762556 0.999356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.497 -0.00972333 -1.3508 399.613 -10.7265 100.389 +EDGE_SE3:QUAT 175 225 0.0106959 -3.0434 -0.204951 0.0370335 -0.000353969 0.0140626 0.999215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.453 -0.00514054 -0.489047 399.588 -11.1018 100.392 +EDGE_SE3:QUAT 176 226 0.0531572 -3.02179 -0.167399 0.026626 0.00604332 -0.000265988 0.999627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.764 0.0161107 3.02437 399.773 -7.9839 100.238 +EDGE_SE3:QUAT 177 227 0.0213529 -3.26506 0.031713 0.0293732 0.00641109 -0.0241407 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.725 0.020758 3.62738 399.723 -8.77694 100.235 +EDGE_SE3:QUAT 178 228 -0.0484436 -3.11359 -0.154497 0.0318068 0.00306897 -0.0571977 0.997851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.634 0.0186924 2.61893 399.689 -9.50657 99.9922 +EDGE_SE3:QUAT 179 229 -0.00643492 -3.05845 -0.118459 0.030578 0.00438757 0.0169967 0.999378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 0.0106633 1.87973 399.713 -9.18414 100.263 +EDGE_SE3:QUAT 180 230 0.115083 -2.96394 -0.0422853 0.0269622 0.00223054 0.0227354 0.999375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 0.00279824 0.746376 399.78 -8.09651 100.169 +EDGE_SE3:QUAT 181 231 -0.0168854 -3.08755 -0.309933 0.0302968 -0.00395739 0.0031255 0.999528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 -0.0124561 -2.03397 399.718 -9.08205 100.286 +EDGE_SE3:QUAT 182 232 0.147606 -3.0981 -0.0701534 0.034948 0.00105675 0.0344259 0.998795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 -0.00472124 -0.19406 399.633 -10.4873 100.248 +EDGE_SE3:QUAT 183 233 -0.00321555 -3.05285 0.0449213 0.0294862 -0.00549504 -0.0206323 0.999337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.0134606 -2.37961 399.728 -8.86479 100.236 +EDGE_SE3:QUAT 184 234 -0.0602762 -3.06792 -0.163193 0.0394736 -0.00312273 -0.0194343 0.999027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.382 -0.00641637 -1.09866 399.529 -11.8456 100.434 +EDGE_SE3:QUAT 185 235 -0.161752 -3.10469 -0.1211 0.0312219 0.00814993 0.00121833 0.999479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 0.0253657 4.04949 399.681 -9.36244 100.338 +EDGE_SE3:QUAT 186 236 0.0346363 -2.96773 -0.0157169 0.0416513 -0.00126196 -0.00456351 0.999121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.307 -0.0036652 -0.516008 399.479 -12.4857 100.519 +EDGE_SE3:QUAT 187 237 0.165213 -2.99257 0.00310385 0.0401383 -0.00230988 -0.014957 0.99908 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.358 -0.00449843 -0.793044 399.515 -12.0391 100.463 +EDGE_SE3:QUAT 188 238 0.0185541 -3.0517 -0.103473 0.0364385 -0.00661003 -0.0109474 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 -0.0218966 -3.06184 399.585 -10.9379 100.414 +EDGE_SE3:QUAT 189 239 -0.0267558 -3.0413 -0.0526275 0.0354981 0.00807454 0.00816753 0.999304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 0.0274781 3.85933 399.597 -10.6544 100.414 +EDGE_SE3:QUAT 190 240 0.0767567 -3.03596 -0.000666132 0.0326296 0.00242457 -0.01353 0.999373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 0.0105707 1.47575 399.678 -9.7772 100.307 +EDGE_SE3:QUAT 191 241 -0.246869 -3.09503 -0.0705801 0.0305328 -0.00618292 0.014952 0.999403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.687 -0.0204618 -3.36264 399.704 -9.13641 100.288 +EDGE_SE3:QUAT 192 242 -0.0467043 -3.0884 -0.213095 0.0255515 0.00704752 -0.00474305 0.999637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.018199 3.59498 399.784 -7.65532 100.229 +EDGE_SE3:QUAT 193 243 -0.126682 -2.94999 -0.20823 0.0293199 -0.000318215 0.000899521 0.99957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00108579 -0.174804 399.742 -8.79213 100.258 +EDGE_SE3:QUAT 194 244 -0.102618 -3.06055 -0.105585 0.0304085 0.00457247 0.0173891 0.999376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.649 0.0111668 1.96666 399.715 -9.13432 100.259 +EDGE_SE3:QUAT 195 245 -0.152002 -3.17768 -0.0386919 0.0366481 0.00487356 -0.00638452 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.498 0.0192431 2.57432 399.587 -10.9802 100.417 +EDGE_SE3:QUAT 196 246 -0.234046 -3.08278 -0.442751 0.0261109 -0.00019206 -0.00158289 0.999658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.000285098 -0.0711781 399.795 -7.83067 100.204 +EDGE_SE3:QUAT 197 247 0.137088 -2.90179 -0.283476 0.0281333 -0.0028378 -0.00625558 0.999581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.00706165 -1.3123 399.76 -8.44011 100.239 +EDGE_SE3:QUAT 198 248 -0.167221 -3.21719 -0.0115691 0.0289362 0.00106039 -0.0190865 0.999398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 0.00616319 0.860875 399.748 -8.67364 100.216 +EDGE_SE3:QUAT 199 249 0.110486 -3.16289 -0.0433531 0.0362304 0.00542152 0.0171555 0.999181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.502 0.0157928 2.33425 399.596 -10.8805 100.381 +EDGE_SE3:QUAT 200 250 -0.0717296 -3.07548 0.0211213 0.0313433 -0.00291675 -0.0050914 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.616 -0.0081953 -1.36137 399.702 -9.40119 100.298 +EDGE_SE3:QUAT 201 251 -0.00681805 -3.17906 -0.346013 0.0273399 0.00355332 -0.00681966 0.999597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 0.0105515 1.88733 399.77 -8.19384 100.229 +EDGE_SE3:QUAT 202 252 0.0431136 -3.00939 -0.0155636 0.0357908 -0.00230337 -0.0199603 0.999157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 -0.00319311 -0.721546 399.614 -10.7402 100.347 +EDGE_SE3:QUAT 203 253 0.131396 -2.95578 -0.00510312 0.0326641 0.0133086 0.01362 0.999285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 0.0447543 6.38344 399.612 -9.82647 100.418 +EDGE_SE3:QUAT 204 254 0.0838311 -3.06117 -0.143531 0.0296023 -0.00392068 -0.0189919 0.999374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.00863256 -1.62102 399.732 -8.89199 100.235 +EDGE_SE3:QUAT 205 255 -0.000913512 -3.09839 -0.126894 0.026556 0.000207912 0.0126952 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.00123814 -0.0983467 399.788 -7.96474 100.195 +EDGE_SE3:QUAT 206 256 -0.0419883 -3.08009 0.02822 0.025427 -0.0011518 -0.00819696 0.999642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 -0.00187783 -0.450506 399.806 -7.6276 100.188 +EDGE_SE3:QUAT 207 257 -0.0163456 -3.02109 -0.162527 0.0277618 0.00905759 -0.0153165 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.812 0.0250572 4.78136 399.734 -8.29606 100.27 +EDGE_SE3:QUAT 208 258 0.0830395 -3.17885 0.0327568 0.023163 -0.0116989 -0.0171338 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.947 -0.0292617 -5.60937 399.786 -6.98522 100.222 +EDGE_SE3:QUAT 209 259 0.0667935 -2.96176 -0.0639898 0.0345535 -0.0028043 0.0256701 0.999069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 -0.0151402 -1.93181 399.637 -10.3462 100.301 +EDGE_SE3:QUAT 210 260 0.0305222 -3.08883 -0.141418 0.032262 -0.00426455 -0.00629449 0.999451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.604 -0.0126125 -2.0085 399.681 -9.6786 100.32 +EDGE_SE3:QUAT 211 261 -0.110706 -3.09079 -0.00819562 0.0274755 0.00109739 -1.72819e-05 0.999622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 0.0030133 0.548611 399.773 -8.2395 100.227 +EDGE_SE3:QUAT 212 262 -0.102122 -3.00302 -0.0615906 0.0303933 -0.00560776 -0.0156984 0.999399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.0148551 -2.51495 399.711 -9.13117 100.271 +EDGE_SE3:QUAT 213 263 -0.179033 -3.1427 -0.0505253 0.0361372 -0.00541643 0.0286585 0.998921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 -0.0248262 -3.32459 399.594 -10.8034 100.338 +EDGE_SE3:QUAT 214 264 0.0658537 -3.04313 0.0580409 0.0293678 0.000268296 -0.0019386 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 0.00112044 0.168193 399.741 -8.80644 100.258 +EDGE_SE3:QUAT 215 265 -0.143185 -3.06723 -0.314008 0.0263857 0.00256175 -0.00587534 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.732 0.00749084 1.37306 399.788 -7.90985 100.21 +EDGE_SE3:QUAT 216 266 -0.0101691 -3.01743 -0.195877 0.0371054 -0.00109091 -0.0434139 0.998367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.45 0.00788509 0.421633 399.586 -11.1369 100.225 +EDGE_SE3:QUAT 217 267 -0.00330242 -3.002 -0.109077 0.0339015 0.0053188 0.00235248 0.999408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 0.0175837 2.60905 399.644 -10.1664 100.364 +EDGE_SE3:QUAT 218 268 -0.218145 -3.15421 -0.0598618 0.0362228 0.00383551 -0.0219894 0.999094 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.506 0.0187597 2.39251 399.599 -10.8431 100.36 +EDGE_SE3:QUAT 219 269 -0.0605602 -2.83477 0.0536274 0.035877 0.00193381 -0.0216238 0.99912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.497 0.0121841 1.43064 399.612 -10.7484 100.344 +EDGE_SE3:QUAT 220 270 0.0970233 -3.10062 -0.0246899 0.0299444 -0.00725552 -0.0069624 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.0210959 -3.5002 399.711 -8.98834 100.299 +EDGE_SE3:QUAT 221 271 0.0456638 -2.9805 -0.0302129 0.0332721 -0.00269205 -0.00550019 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.565 -0.00778321 -1.23491 399.665 -9.97895 100.334 +EDGE_SE3:QUAT 222 272 0.148506 -3.07901 -0.218243 0.0376311 0.00356207 0.0181903 0.99912 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.442 0.00847643 1.36778 399.571 -11.2947 100.398 +EDGE_SE3:QUAT 223 273 -0.0556997 -3.18523 -0.235704 0.0389589 -0.00356631 0.0206032 0.999022 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.421 -0.0193808 -2.26153 399.538 -11.6644 100.426 +EDGE_SE3:QUAT 224 274 -0.0250337 -3.14967 -0.163133 0.0250374 -0.00147102 0.0289246 0.999267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.00703749 -1.16888 399.81 -7.5013 100.108 +EDGE_SE3:QUAT 225 275 -0.127119 -2.98858 -0.00343526 0.0336081 0.00445968 -0.0175222 0.999272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.584 0.0181048 2.58039 399.652 -10.061 100.325 +EDGE_SE3:QUAT 226 276 0.229636 -3.10875 -0.0812266 0.0284245 0.00750058 0.0428088 0.998651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 0.0172868 3.01218 399.738 -8.58999 100.089 +EDGE_SE3:QUAT 227 277 -0.0786455 -3.13901 -0.0697428 0.0267717 0.00929853 -0.00619399 0.999579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 0.0248305 4.7471 399.75 -8.01538 100.274 +EDGE_SE3:QUAT 228 278 0.144844 -3.10515 -0.272418 0.023607 -0.00561097 -0.00883668 0.999667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.814 -0.0127201 -2.679 399.821 -7.08963 100.18 +EDGE_SE3:QUAT 229 279 0.135237 -3.10469 0.106597 0.0395579 -0.0089755 0.0110872 0.999115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.0372054 -4.74552 399.497 -11.8358 100.518 +EDGE_SE3:QUAT 230 280 -0.027205 -3.18812 -0.0374326 0.0350868 0.00388434 -0.00176737 0.999375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.528 0.0139888 1.97732 399.625 -10.5178 100.38 +EDGE_SE3:QUAT 231 281 0.116528 -3.07257 -0.205221 0.0341974 -0.0156403 0.0171134 0.999146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.883 -0.0497558 -8.16879 399.548 -10.1936 100.504 +EDGE_SE3:QUAT 232 282 0.102083 -3.10287 -0.150421 0.0234528 -0.00168547 -0.0139746 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 -0.00245555 -0.645576 399.834 -7.0388 100.147 +EDGE_SE3:QUAT 233 283 0.0656143 -3.1271 -0.00171123 0.0400286 0.00398925 0.00881292 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.375 0.0133069 1.78013 399.513 -12.0057 100.482 +EDGE_SE3:QUAT 234 284 -0.000547869 -3.10502 -0.171998 0.0270819 0.00232285 -0.00590214 0.999613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 0.00708221 1.25653 399.778 -8.11878 100.221 +EDGE_SE3:QUAT 235 285 -0.0816881 -2.81858 -0.172729 0.037053 -0.00510996 -0.0240792 0.99901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 -0.0130146 -2.01559 399.579 -11.1335 100.367 +EDGE_SE3:QUAT 236 286 0.0484962 -3.03673 -0.273522 0.0314552 -0.00116317 -0.0226231 0.999248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.604 0.00081882 -0.154046 399.703 -9.43795 100.246 +EDGE_SE3:QUAT 237 287 -0.032727 -3.13576 -0.16107 0.0288657 -0.00529622 0.030753 0.999096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0182354 -3.17671 399.737 -8.62404 100.181 +EDGE_SE3:QUAT 238 288 -0.0496857 -3.07509 -0.251657 0.0344279 -0.00101305 -0.0100134 0.999357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.526 -0.00111412 -0.299182 399.644 -10.3244 100.346 +EDGE_SE3:QUAT 239 289 0.0193968 -2.92723 -0.142801 0.0340278 0.000981465 0.0223835 0.99917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 -0.00184943 0.0332544 399.652 -10.2077 100.298 +EDGE_SE3:QUAT 240 290 -0.0211913 -2.98593 -0.0887671 0.0291385 -0.00873823 -0.0167197 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.0246598 -4.07333 399.716 -8.76599 100.275 +EDGE_SE3:QUAT 241 291 0.086062 -3.04769 -0.116784 0.0355579 0.00663059 -0.0198717 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 0.0266325 3.73489 399.601 -10.6335 100.377 +EDGE_SE3:QUAT 242 292 0.00631038 -3.09328 0.107673 0.027938 0.00270555 0.0138245 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 0.00551941 1.11994 399.763 -8.38576 100.219 +EDGE_SE3:QUAT 243 293 -0.0706993 -3.09109 -0.0811525 0.0348635 0.00157083 0.00963527 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.515 0.0031472 0.583027 399.635 -10.4558 100.357 +EDGE_SE3:QUAT 244 294 -0.0228583 -3.2339 -0.0736715 0.0229755 -0.000304831 -0.0145165 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.789 0.000832623 0.04775 399.842 -6.89195 100.137 +EDGE_SE3:QUAT 245 295 0.133367 -3.07528 -0.259682 0.0281729 0.0101667 0.0147931 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 0.0288509 4.8302 399.722 -8.47688 100.284 +EDGE_SE3:QUAT 246 296 -0.0569526 -2.8712 -0.0547276 0.0364743 -0.000370541 0.00807149 0.999302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.469 -0.0034872 -0.361598 399.601 -10.9345 100.393 +EDGE_SE3:QUAT 247 297 0.0586638 -2.97212 -0.0881569 0.0253631 0.00604715 0.0425353 0.998755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.0116432 2.37025 399.795 -7.65984 100.031 +EDGE_SE3:QUAT 248 298 0.175276 -3.06391 0.226309 0.0376879 0.00576512 0.0634035 0.997259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.437 0.00471442 1.43727 399.564 -11.3789 100.035 +EDGE_SE3:QUAT 249 299 -0.0558853 -3.02436 -0.136848 0.0348942 0.00387508 0.0125757 0.999304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.527 0.0106922 1.67202 399.629 -10.4716 100.358 +EDGE_SE3:QUAT 250 300 -0.133213 -3.12674 -0.0957537 0.0362179 -0.00392101 -0.00565905 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 -0.0128257 -1.83529 399.601 -10.8624 100.4 +EDGE_SE3:QUAT 251 301 -0.0651135 -3.03122 -0.170269 0.0340945 0.00352503 0.0276197 0.999031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.541 0.0058761 1.19482 399.647 -10.243 100.278 +EDGE_SE3:QUAT 252 302 -0.0288678 -3.09016 -0.0523891 0.0254668 -0.00235219 -0.0187731 0.999497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 -0.00366009 -0.888282 399.804 -7.64677 100.162 +EDGE_SE3:QUAT 253 303 -0.144662 -3.20284 -0.133085 0.0400399 -0.00108619 -0.0126626 0.999117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.359 -0.000284093 -0.238205 399.519 -12.0054 100.465 +EDGE_SE3:QUAT 254 304 -0.0576414 -2.97553 0.0633291 0.0314163 0.000369935 -0.0136912 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.00384386 0.442749 399.704 -9.41951 100.278 +EDGE_SE3:QUAT 255 305 0.204381 -3.09634 -0.21618 0.0403396 -0.00188346 -0.0141485 0.999084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.35 -0.00301142 -0.597945 399.511 -12.0977 100.47 +EDGE_SE3:QUAT 256 306 -0.0455904 -3.09673 -0.0862219 0.027381 0.00993045 0.00896205 0.999536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 0.0274032 4.81582 399.737 -8.2272 100.283 +EDGE_SE3:QUAT 257 307 -0.0810938 -3.07172 0.0394254 0.0376958 -0.000102891 0.000883481 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.432 -0.000637625 -0.0713524 399.574 -11.3007 100.426 +EDGE_SE3:QUAT 258 308 -0.038977 -2.98935 -0.041741 0.0258616 0.00248157 0.0281403 0.999266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 0.00278618 0.802718 399.797 -7.77082 100.124 +EDGE_SE3:QUAT 259 309 0.117742 -3.02558 -0.291466 0.0345744 -0.00814507 0.00735787 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 -0.0289912 -4.22162 399.614 -10.3524 100.402 +EDGE_SE3:QUAT 260 310 0.0983486 -3.04401 0.0630866 0.0323535 0.0037942 0.0106661 0.999412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 0.0102457 1.68821 399.681 -9.70896 100.311 +EDGE_SE3:QUAT 261 311 0.103972 -3.23229 -0.132702 0.0302105 -0.00516887 -0.0202022 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 -0.0126421 -2.21545 399.717 -9.08006 100.248 +EDGE_SE3:QUAT 262 312 -0.146462 -3.2258 -0.024178 0.0277582 -0.00139817 -0.0272425 0.999242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.000308164 -0.24464 399.768 -8.33288 100.157 +EDGE_SE3:QUAT 263 313 0.041537 -3.11484 -0.211902 0.0261046 0.00684541 -0.0185311 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.801 0.0185946 3.71047 399.775 -7.80275 100.207 +EDGE_SE3:QUAT 264 314 0.0122075 -2.67492 -0.159409 0.0288364 -0.00556474 0.0217075 0.999333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0181278 -3.15502 399.737 -8.62301 100.228 +EDGE_SE3:QUAT 265 315 0.0623737 -3.07501 -0.135195 0.0338797 0.00235123 0.0235945 0.999145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 0.00262327 0.694457 399.654 -10.1701 100.291 +EDGE_SE3:QUAT 266 316 0.0202681 -3.02132 -0.108423 0.031823 -0.0040487 0.00130946 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 -0.013092 -2.04762 399.69 -9.5406 100.315 +EDGE_SE3:QUAT 267 317 -0.157225 -3.18032 -0.0391657 0.0257185 -0.00192126 0.0238048 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.00779597 -1.32679 399.799 -7.70445 100.146 +EDGE_SE3:QUAT 268 318 0.227863 -2.92362 -0.0551483 0.0313104 -0.00987817 -0.0170931 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.0302597 -4.6137 399.669 -9.42068 100.327 +EDGE_SE3:QUAT 269 319 0.150875 -3.14073 0.056212 0.0280183 -0.0118359 -0.022205 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.842 -0.0347272 -5.54019 399.711 -8.45278 100.276 +EDGE_SE3:QUAT 270 320 0.0302405 -2.94097 0.0195797 0.0260863 0.00345441 -0.000700841 0.999653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.00908332 1.73719 399.791 -7.82252 100.213 +EDGE_SE3:QUAT 271 321 0.111483 -2.98989 -0.0668654 0.0275413 -0.000932963 -0.0278325 0.999233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.00165679 -0.00614715 399.772 -8.26552 100.15 +EDGE_SE3:QUAT 272 322 -0.0252455 -3.08534 -0.0673068 0.0293862 -0.00143826 -0.00958966 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00258557 -0.549485 399.74 -8.81492 100.251 +EDGE_SE3:QUAT 273 323 0.0460613 -3.01295 -0.117746 0.0227117 0.00380701 0.0214704 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.00683673 1.60939 399.84 -6.82845 100.117 +EDGE_SE3:QUAT 274 324 0.00630421 -3.02644 -0.0487656 0.0294714 -0.00100349 0.0111715 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 -0.00485484 -0.69878 399.739 -8.83547 100.249 +EDGE_SE3:QUAT 275 325 0.158625 -3.15376 -0.134453 0.025198 0.00833262 0.019597 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.822 0.0206606 3.86704 399.783 -7.58898 100.196 +EDGE_SE3:QUAT 276 326 0.048248 -2.98662 -0.0409321 0.0216411 0.000554023 0.000705275 0.999765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.813 0.00113217 0.267738 399.859 -6.49087 100.141 +EDGE_SE3:QUAT 277 327 0.13536 -3.03136 -0.0904836 0.0367094 -0.00667851 0.00272437 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.521 -0.025002 -3.39572 399.578 -11.0005 100.435 +EDGE_SE3:QUAT 278 328 0.0149143 -3.15991 -0.126968 0.0263953 -0.000238494 1.04532e-05 0.999652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.00063009 -0.119338 399.791 -7.91584 100.209 +EDGE_SE3:QUAT 279 329 0.0451922 -3.16909 -0.140876 0.030454 -0.00280005 0.0118333 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.0104915 -1.6149 399.718 -9.12531 100.271 +EDGE_SE3:QUAT 280 330 0.0695638 -3.07913 -0.0356025 0.0240803 0.00012876 -0.0155371 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.00210304 0.288754 399.826 -7.22189 100.15 +EDGE_SE3:QUAT 281 331 0.0315745 -3.1598 -0.233664 0.0308576 0.00102548 0.012998 0.999439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 0.000691824 0.271659 399.714 -9.25578 100.269 +EDGE_SE3:QUAT 282 332 -0.0577875 -2.93112 -0.122457 0.0294526 -0.00130575 0.0245169 0.999265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 -0.00789755 -1.08508 399.739 -8.82633 100.203 +EDGE_SE3:QUAT 283 333 -0.0268156 -2.75783 -0.115114 0.027277 0.00828257 0.00556618 0.999578 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 0.022445 4.04822 399.75 -8.18797 100.267 +EDGE_SE3:QUAT 284 334 -0.0721355 -3.09307 -0.013885 0.0342649 -0.000615824 -0.0224174 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.53 0.00315508 0.153175 399.648 -10.2771 100.302 +EDGE_SE3:QUAT 285 335 0.150753 -2.80772 -0.149334 0.0300947 -0.0174877 -0.0275386 0.999015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.983 -0.0616462 -8.24099 399.612 -9.11532 100.393 +EDGE_SE3:QUAT 286 336 0.0608423 -3.02065 -0.0145856 0.0280017 0.00688504 0.0138651 0.999488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 0.0181417 3.20704 399.747 -8.41568 100.246 +EDGE_SE3:QUAT 287 337 -0.0255246 -3.05047 -0.185222 0.0353639 -0.00296278 0.000748255 0.99937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 -0.0106299 -1.49564 399.621 -10.6018 100.381 +EDGE_SE3:QUAT 288 338 0.0331453 -3.00436 -0.0687598 0.0293784 -0.00194782 -0.0197513 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00236417 -0.6248 399.74 -8.81794 100.221 +EDGE_SE3:QUAT 289 339 0.0314378 -2.99084 -0.0456048 0.0302394 -0.000194118 -0.0256762 0.999213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 0.00408898 0.368696 399.725 -9.06966 100.209 +EDGE_SE3:QUAT 290 340 0.0876317 -3.21416 -0.0478817 0.036547 -0.00848497 0.0168609 0.999154 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.578 -0.0329892 -4.60732 399.568 -10.9264 100.429 +EDGE_SE3:QUAT 291 341 -0.0927587 -3.09953 0.0212842 0.0255886 -0.00221757 0.00273842 0.999666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.00600075 -1.15018 399.802 -7.67275 100.199 +EDGE_SE3:QUAT 292 342 -0.152173 -3.15096 0.123591 0.0387786 -0.00139512 0.020742 0.999032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.406 -0.0114356 -1.17868 399.547 -11.6197 100.411 +EDGE_SE3:QUAT 293 343 -0.0792689 -2.99066 -0.176326 0.0256928 -0.0029596 0.0216397 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 -0.00995758 -1.81186 399.798 -7.69284 100.16 +EDGE_SE3:QUAT 294 344 -0.0749327 -3.07287 -0.169298 0.0267224 0.000148698 0.000489355 0.999643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.000326941 0.066457 399.786 -8.01389 100.214 +EDGE_SE3:QUAT 295 345 -0.0298243 -3.06462 -0.058291 0.0355271 -0.00351229 0.0159912 0.999235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.519 -0.0159979 -2.0946 399.616 -10.6402 100.364 +EDGE_SE3:QUAT 296 346 -0.208389 -3.11332 -0.158929 0.032124 -0.000991137 0.0212436 0.999258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 -0.00744459 -0.904177 399.69 -9.62867 100.266 +EDGE_SE3:QUAT 297 347 0.00397964 -3.16043 -0.229948 0.0310241 -0.00685939 0.038272 0.998762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.0240803 -4.13521 399.689 -9.25096 100.186 +EDGE_SE3:QUAT 298 348 0.0542878 -2.83593 0.0760777 0.0321705 -0.0006488 0.003236 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 -0.00274903 -0.386536 399.689 -9.64575 100.31 +EDGE_SE3:QUAT 299 349 0.0954617 -2.9754 -0.130473 0.0326043 0.00319307 0.0391873 0.998695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 0.00227468 0.826855 399.678 -9.80355 100.169 +EDGE_SE3:QUAT 300 350 -0.0343199 -3.01386 -0.138736 0.0269678 0.00564419 0.00675913 0.999598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.747 0.0145925 2.71106 399.769 -8.09447 100.235 +EDGE_SE3:QUAT 301 351 0.265006 -3.15289 -0.019854 0.023721 0.00458076 -0.0100733 0.999657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.0115719 2.43256 399.822 -7.10477 100.175 +EDGE_SE3:QUAT 302 352 -0.117375 -3.10649 -0.151037 0.021618 -0.00535254 0.0170179 0.999607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.858 -0.0121507 -2.89549 399.848 -6.46544 100.134 +EDGE_SE3:QUAT 303 353 -0.1724 -3.12157 0.204506 0.024794 -0.00919525 -0.0311096 0.999166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.839 -0.0228827 -4.12936 399.785 -7.49302 100.139 +EDGE_SE3:QUAT 304 354 0.0457296 -3.00187 -0.21433 0.0293582 0.00781111 0.00520461 0.999525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 0.0225917 3.81153 399.718 -8.81054 100.297 +EDGE_SE3:QUAT 305 355 0.0365762 -3.20068 -0.120433 0.0355921 -0.00258621 0.0101154 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.506 -0.0115845 -1.50749 399.617 -10.6656 100.376 +EDGE_SE3:QUAT 306 356 -0.0840794 -2.99812 -0.0461709 0.0315281 0.00638119 0.0137583 0.999388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 0.0182292 2.92735 399.687 -9.47074 100.305 +EDGE_SE3:QUAT 307 357 0.123624 -3.1738 -0.232172 0.035716 0.000614083 8.41826e-05 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 0.00216629 0.304886 399.617 -10.708 100.383 +EDGE_SE3:QUAT 308 358 0.184947 -2.95908 0.074224 0.0363416 0.00115451 0.0116231 0.999271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.472 0.00112603 0.323179 399.603 -10.8982 100.383 +EDGE_SE3:QUAT 309 359 -0.0679075 -2.92765 0.0616984 0.0305082 -0.00110026 0.0506066 0.998252 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 -0.0120637 -1.47374 399.719 -9.14074 100.028 +EDGE_SE3:QUAT 310 360 -0.0660665 -3.25747 -0.0252614 0.0246261 -0.00473608 -0.0229666 0.999422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.778 -0.00956593 -2.0265 399.81 -7.40769 100.142 +EDGE_SE3:QUAT 311 361 -0.0881092 -2.99737 -0.115497 0.0255966 0.00497585 0.00328575 0.999655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.0124415 2.43618 399.794 -7.67929 100.212 +EDGE_SE3:QUAT 312 362 -0.0289822 -3.03785 -0.0624406 0.0354304 0.00268281 -0.0188923 0.99919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.515 0.0138296 1.74095 399.62 -10.6126 100.348 +EDGE_SE3:QUAT 313 363 -0.151813 -3.28227 -0.277165 0.0272121 -0.00151388 0.0115922 0.999561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.709 -0.00575802 -0.945571 399.777 -8.15722 100.211 +EDGE_SE3:QUAT 314 364 -0.00254953 -3.19376 -0.00343866 0.0170308 0.00369917 -0.0176772 0.999692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.906 0.0068088 2.02931 399.907 -5.09549 100.067 +EDGE_SE3:QUAT 315 365 0.0155068 -2.96301 -0.179671 0.0256498 0.00384584 -0.00726525 0.999637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 0.0105991 2.0336 399.796 -7.68657 100.203 +EDGE_SE3:QUAT 316 366 0.0664133 -3.11125 -0.0599331 0.0314573 -0.000759964 0.0277048 0.999121 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 -0.00772075 -0.902 399.702 -9.42943 100.222 +EDGE_SE3:QUAT 317 367 -0.1074 -3.00215 0.0437778 0.0293267 0.00063361 -0.00527952 0.999556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 0.00275663 0.409424 399.742 -8.79358 100.256 +EDGE_SE3:QUAT 318 368 0.0884503 -3.14416 -0.241082 0.0392396 -0.00040046 -0.00287583 0.999226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.384 -0.000682014 -0.132278 399.538 -11.7631 100.461 +EDGE_SE3:QUAT 319 369 -0.129026 -3.04014 0.0962665 0.0382487 0.00286383 -0.00393644 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.427 0.0120118 1.52036 399.558 -11.4637 100.444 +EDGE_SE3:QUAT 320 370 0.0266504 -3.09222 -0.0154214 0.0417381 -0.000369724 -0.00800656 0.999096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.303 0.0012495 0.0158251 399.477 -12.5112 100.516 +EDGE_SE3:QUAT 321 371 0.0231897 -3.04714 -0.174079 0.0246469 -0.000415782 0.00400831 0.999688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.00150839 -0.267038 399.818 -7.39151 100.181 +EDGE_SE3:QUAT 322 372 0.0857668 -3.07846 -0.175278 0.0255754 0.00242071 0.0107777 0.999612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.00486091 1.04418 399.802 -7.67539 100.188 +EDGE_SE3:QUAT 323 373 0.0151937 -3.11577 -0.0335541 0.0308638 -0.00383022 0.0356679 0.99888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 -0.0169764 -2.57159 399.706 -9.22877 100.175 +EDGE_SE3:QUAT 324 374 -0.0533005 -2.9534 -0.0210836 0.0282153 -0.00241753 -0.00697655 0.999575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.688 -0.00576162 -1.08979 399.759 -8.46454 100.238 +EDGE_SE3:QUAT 325 375 -0.0850833 -3.09657 0.0424286 0.0312084 -0.00211762 -0.0225255 0.999257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 -0.00228128 -0.635813 399.706 -9.36826 100.243 +EDGE_SE3:QUAT 326 376 0.0681386 -3.14417 -0.0568083 0.0270682 0.00564326 0.0183421 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 0.0134334 2.52132 399.769 -8.13812 100.205 +EDGE_SE3:QUAT 327 377 -0.0986384 -3.04283 -0.00246123 0.0341454 0.00670607 0.010815 0.999336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.583 0.0211265 3.12808 399.633 -10.2513 100.367 +EDGE_SE3:QUAT 328 378 0.0270612 -3.18904 0.0068394 0.0292084 0.00190021 -0.0294394 0.999138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.0101357 1.46432 399.742 -8.74868 100.174 +EDGE_SE3:QUAT 329 379 0.0423988 -3.14623 0.00629121 0.036536 -0.00426733 0.0216847 0.999088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.503 -0.0203236 -2.60557 399.591 -10.9351 100.371 +EDGE_SE3:QUAT 330 380 0.0400586 -3.17669 -0.00120155 0.0371641 -0.00449097 -0.0032339 0.999294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.472 -0.0158734 -2.17073 399.578 -11.1439 100.427 +EDGE_SE3:QUAT 331 381 0.0515707 -2.98244 -0.119449 0.0336856 -0.00318599 0.00672808 0.999405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.562 -0.0120962 -1.72731 399.655 -10.0954 100.344 +EDGE_SE3:QUAT 332 382 -0.121467 -3.06315 -0.137284 0.0425933 0.00298551 -0.00468248 0.999077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.288 0.0142865 1.60994 399.452 -12.7633 100.549 +EDGE_SE3:QUAT 333 383 0.0810237 -2.98352 -0.079982 0.0307456 4.55339e-05 -0.00932897 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.0019005 0.194782 399.716 -9.21937 100.275 +EDGE_SE3:QUAT 334 384 -0.0612038 -3.14884 0.0278424 0.0369556 0.00354313 -0.0155871 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.478 0.0168337 2.11459 399.584 -11.068 100.397 +EDGE_SE3:QUAT 335 385 -0.0917869 -2.89855 -0.0774573 0.0378211 -0.0025086 -0.0242622 0.998987 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.429 -0.00261882 -0.701817 399.569 -11.3514 100.373 +EDGE_SE3:QUAT 336 386 0.023934 -3.0237 -0.194363 0.0305753 -0.00232276 0.00983301 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 -0.00880377 -1.34067 399.717 -9.16371 100.275 +EDGE_SE3:QUAT 337 387 0.112594 -3.22375 -0.258141 0.0309382 0.00308049 -0.0205995 0.999304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.637 0.0129299 1.92066 399.708 -9.26464 100.254 +EDGE_SE3:QUAT 338 388 -0.122149 -3.1064 -0.180947 0.0267202 -5.1618e-05 0.0265091 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.00388986 -0.450574 399.786 -8.01385 100.144 +EDGE_SE3:QUAT 339 389 -0.122625 -3.14797 -0.063126 0.0356018 0.00111992 -0.0103849 0.999311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.496 0.00656483 0.781008 399.619 -10.6716 100.371 +EDGE_SE3:QUAT 340 390 0.0557067 -3.0186 -0.180773 0.0299165 0.0101248 -0.0200005 0.999301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.797 0.0297724 5.41775 399.688 -8.92848 100.308 +EDGE_SE3:QUAT 341 391 -0.0238847 -3.08454 -0.120323 0.0320124 -0.00505134 -0.0255907 0.999147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 -0.011689 -2.03067 399.684 -9.62529 100.255 +EDGE_SE3:QUAT 342 392 0.0492906 -3.05011 -0.0925048 0.0324379 0.0116915 -0.0212817 0.999179 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.786 0.0366235 6.25548 399.626 -9.67354 100.376 +EDGE_SE3:QUAT 343 393 0.18446 -2.95983 -0.0489129 0.0319108 0.00642979 -0.0193442 0.999283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 0.0226984 3.58178 399.676 -9.54288 100.302 +EDGE_SE3:QUAT 344 394 0.0987677 -3.08234 -0.146997 0.0312386 -0.00599617 0.00826079 0.99946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.0197494 -3.15051 399.692 -9.35629 100.313 +EDGE_SE3:QUAT 345 395 -0.0766605 -3.20372 -0.188753 0.0272742 -0.00216039 -0.00047583 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.0058177 -1.0717 399.775 -8.17931 100.226 +EDGE_SE3:QUAT 346 396 -0.0504546 -3.05566 -0.0827472 0.0317521 0.00667976 0.00214679 0.999471 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.653 0.0209372 3.29644 399.68 -9.52268 100.333 +EDGE_SE3:QUAT 347 397 0.109153 -3.0851 -0.209512 0.0268535 0.000464177 0.00818679 0.999606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 6.50547e-05 0.100052 399.784 -8.05398 100.21 +EDGE_SE3:QUAT 348 398 0.0309543 -3.08974 -0.13822 0.0260678 0.00434084 0.0184214 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 0.00928223 1.88048 399.789 -7.83382 100.181 +EDGE_SE3:QUAT 349 399 0.0265289 -2.91285 0.0861061 0.0332242 -0.00432908 -0.0169636 0.999295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.0110316 -1.82389 399.662 -9.97658 100.313 +EDGE_SE3:QUAT 350 400 -0.0421807 -3.24188 0.065461 0.0320506 -0.00495049 -0.00177143 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 -0.0155605 -2.4391 399.682 -9.61143 100.325 +EDGE_SE3:QUAT 351 401 0.0413224 -3.1157 -0.233956 0.0330012 0.000686172 -0.00622629 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 0.00360573 0.465978 399.673 -9.89417 100.323 +EDGE_SE3:QUAT 352 402 -0.083502 -3.1765 -0.257381 0.0352665 0.000291656 -0.0317505 0.998873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.506 0.00878962 0.816879 399.626 -10.5732 100.274 +EDGE_SE3:QUAT 353 403 -0.0650663 -3.24076 -0.139133 0.0312569 0.000301776 -0.00776775 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 0.002454 0.296375 399.707 -9.3721 100.287 +EDGE_SE3:QUAT 354 404 -0.192399 -3.05254 -0.0205584 0.0302911 -6.76313e-05 -0.00694258 0.999517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 0.00106866 0.0923523 399.725 -9.08333 100.27 +EDGE_SE3:QUAT 355 405 -0.0605368 -2.91813 0.151889 0.0329513 0.00833703 -0.0290863 0.998999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 0.0292148 4.73764 399.643 -9.83078 100.3 +EDGE_SE3:QUAT 356 406 0.0697443 -3.11318 -0.0605606 0.0304918 -0.00441025 0.0157958 0.9994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.0156787 -2.4919 399.712 -9.12917 100.27 +EDGE_SE3:QUAT 357 407 -0.052607 -3.14251 -0.256375 0.0368186 5.93931e-05 -0.0218409 0.999083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 0.00610178 0.511846 399.593 -11.0387 100.36 +EDGE_SE3:QUAT 358 408 0.112514 -2.98367 0.0173553 0.0302206 -0.00397553 0.0190523 0.999354 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.664 -0.0147536 -2.33101 399.719 -9.04697 100.252 +EDGE_SE3:QUAT 359 409 -0.0525742 -3.20008 -0.0944529 0.0246018 -0.00201429 -0.0343422 0.999105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.758 -0.00086193 -0.4989 399.817 -7.39359 100.065 +EDGE_SE3:QUAT 360 410 -0.18415 -2.94843 -0.074468 0.0284 -0.000398302 -0.00896463 0.999556 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.677 0.000316022 -0.04628 399.758 -8.51739 100.234 +EDGE_SE3:QUAT 361 411 -0.0716385 -3.01298 -0.0871289 0.0325708 -0.00181406 -0.00826237 0.999434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.578 -0.00417831 -0.744704 399.681 -9.76912 100.313 +EDGE_SE3:QUAT 362 412 0.0542683 -3.23037 -0.117154 0.0339586 0.000625394 0.00525707 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 0.000908784 0.205293 399.654 -10.1824 100.343 +EDGE_SE3:QUAT 363 413 0.013873 -3.02507 -0.102966 0.0410017 -0.00240642 0.00245607 0.999153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.336 -0.0106332 -1.2618 399.493 -12.2888 100.508 +EDGE_SE3:QUAT 364 414 -0.0182592 -2.94417 -0.00237069 0.0319557 -5.16397e-05 0.0073715 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 -0.00166816 -0.167081 399.694 -9.58181 100.301 +EDGE_SE3:QUAT 365 415 -0.11561 -3.28737 -0.263701 0.029174 -0.00183476 0.0228224 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 -0.00895817 -1.3156 399.743 -8.74071 100.207 +EDGE_SE3:QUAT 366 416 0.0202636 -2.92963 -0.109526 0.0343921 -0.000680823 0.0276637 0.999025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 -0.00872988 -0.910307 399.644 -10.309 100.28 +EDGE_SE3:QUAT 367 417 -0.0540784 -3.02968 0.04813 0.0269495 0.000726112 0.00378199 0.999629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 0.00140741 0.301676 399.782 -8.08246 100.217 +EDGE_SE3:QUAT 368 418 -0.175451 -3.09671 -0.0820867 0.0300608 -0.000734277 -0.030738 0.999075 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.00334792 0.187535 399.729 -9.02008 100.177 +EDGE_SE3:QUAT 369 419 0.0532406 -3.03388 -0.175604 0.0225554 -7.74356e-06 0.00520177 0.999732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.797 -0.00054642 -0.0742542 399.847 -6.76492 100.15 +EDGE_SE3:QUAT 370 420 -0.0564968 -3.09617 -0.0723869 0.0201923 -0.003062 0.0105695 0.999736 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.852 -0.00683546 -1.65839 399.874 -6.04993 100.119 +EDGE_SE3:QUAT 371 421 -0.0627655 -3.09987 -0.098957 0.0302133 -0.00192912 0.017492 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 -0.00881327 -1.2805 399.724 -9.05343 100.247 +EDGE_SE3:QUAT 372 422 -0.171848 -3.312 -0.154478 0.0352641 -0.00439652 -0.013362 0.999279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.521 -0.0125114 -1.91294 399.62 -10.5843 100.366 +EDGE_SE3:QUAT 373 423 -0.0468701 -3.1413 -0.0624481 0.0329464 -0.00369571 -0.00114917 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.583 -0.0119339 -1.82342 399.669 -9.87907 100.335 +EDGE_SE3:QUAT 374 424 0.088291 -3.02906 -0.155652 0.0332345 0.0019345 0.011198 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.00398944 0.742979 399.667 -9.96933 100.321 +EDGE_SE3:QUAT 375 425 0.207394 -2.91419 -0.114998 0.0221803 0.00228063 -0.0046344 0.999741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.811 0.00546275 1.20148 399.85 -6.65025 100.149 +EDGE_SE3:QUAT 376 426 0.0181117 -3.01259 0.000238796 0.0300561 0.004548 -0.00600728 0.99952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 0.0144984 2.38058 399.72 -9.00683 100.283 +EDGE_SE3:QUAT 377 427 -0.041838 -3.06789 -0.0795635 0.0245757 0.0124291 -0.00335339 0.999615 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.963 0.0301505 6.264 399.757 -7.35928 100.289 +EDGE_SE3:QUAT 378 428 0.0931215 -2.97914 -0.308081 0.0353569 0.00929637 -0.00603543 0.999313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 0.0334253 4.77235 399.59 -10.5869 100.434 +EDGE_SE3:QUAT 379 429 0.0257219 -3.1835 -0.15155 0.0303676 -0.00919621 0.0231377 0.999229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 -0.0281179 -5.01538 399.687 -9.06211 100.29 +EDGE_SE3:QUAT 380 430 -0.0319896 -3.33208 -0.0583484 0.0285486 0.00108923 -0.0234717 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 0.00678904 0.945828 399.755 -8.55669 100.191 +EDGE_SE3:QUAT 381 431 0.126897 -3.13356 -0.14294 0.038003 0.00606075 -0.00658247 0.999238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.475 0.0244277 3.17681 399.551 -11.3836 100.456 +EDGE_SE3:QUAT 382 432 0.0565417 -3.26596 -0.108116 0.0270534 -0.000322331 0.0119553 0.999562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.00261026 -0.355041 399.78 -8.11245 100.206 +EDGE_SE3:QUAT 383 433 0.07558 -3.15481 -0.213848 0.0281838 -0.00451394 -0.00100604 0.999592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.012588 -2.2385 399.754 -8.45226 100.252 +EDGE_SE3:QUAT 384 434 0.0770277 -3.0559 0.0140446 0.0311042 -0.00261241 0.0262447 0.999168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 -0.012609 -1.79388 399.706 -9.31381 100.229 +EDGE_SE3:QUAT 385 435 -0.0283599 -3.1751 -0.271241 0.0340864 0.00581728 0.00909678 0.999361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.573 0.0181808 2.71967 399.639 -10.2299 100.362 +EDGE_SE3:QUAT 386 436 0.1967 -3.05667 -0.0109382 0.0355923 -0.000570551 -0.00698881 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.000257036 -0.135755 399.62 -10.6718 100.375 +EDGE_SE3:QUAT 387 437 0.109931 -2.92796 0.0553454 0.0178209 -0.00787941 0.00622309 0.999791 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.957 -0.0137456 -4.00589 399.88 -5.33479 100.136 +EDGE_SE3:QUAT 388 438 0.00671874 -3.11942 -0.0945887 0.0256028 -0.00316727 0.000265638 0.999667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.751 -0.00813155 -1.58683 399.799 -7.67795 100.204 +EDGE_SE3:QUAT 389 439 0.032196 -3.17175 -0.172647 0.0250684 -0.00345848 -0.0124604 0.999602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.00731293 -1.5407 399.807 -7.52679 100.18 +EDGE_SE3:QUAT 390 440 -0.033753 -3.14126 -0.147433 0.0358168 0.00410739 0.0380627 0.998625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 0.00536532 1.23141 399.61 -10.7719 100.247 +EDGE_SE3:QUAT 391 441 -0.0315664 -3.1566 -0.00745872 0.0327647 -0.00705951 -0.0102239 0.999386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 -0.0217452 -3.32558 399.659 -9.83762 100.344 +EDGE_SE3:QUAT 392 442 -0.0306541 -3.08218 0.0422496 0.0300895 -0.000394804 -0.00334208 0.999542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.000581379 -0.136921 399.728 -9.02303 100.271 +EDGE_SE3:QUAT 393 443 0.102152 -3.07496 -0.0456719 0.0282554 -0.000879072 -0.00685624 0.999577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.00139099 -0.322999 399.76 -8.47448 100.235 +EDGE_SE3:QUAT 394 444 -0.0507474 -3.10341 0.0431926 0.0366342 -0.0019359 -0.00266198 0.999323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 -0.00637574 -0.908297 399.596 -10.9838 100.404 +EDGE_SE3:QUAT 395 445 -0.0172256 -3.22721 -0.117645 0.03083 -0.00223873 -0.0214675 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 -0.00289619 -0.721025 399.713 -9.25488 100.241 +EDGE_SE3:QUAT 396 446 0.106587 -3.11316 0.0185749 0.0241711 -0.00342765 -0.0103787 0.999648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 -0.00725076 -1.56232 399.82 -7.25629 100.172 +EDGE_SE3:QUAT 397 447 -0.0201798 -3.03708 -0.0914904 0.0327516 -0.0010838 -0.00577596 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 -0.00231151 -0.427901 399.678 -9.82149 100.319 +EDGE_SE3:QUAT 398 448 -0.147206 -3.16075 -0.0171375 0.0327786 -0.00312527 -0.0308121 0.998983 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 -0.00382323 -0.954213 399.675 -9.84902 100.231 +EDGE_SE3:QUAT 399 449 -0.104981 -3.10923 -0.0205621 0.030197 0.000424245 -0.00594333 0.999526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.00235805 0.319591 399.726 -9.05451 100.27 +EDGE_SE3:QUAT 400 450 -0.203892 -3.06867 0.0130038 0.0257613 -0.00561727 -0.0181003 0.999488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.766 -0.0129082 -2.52664 399.789 -7.74608 100.185 +EDGE_SE3:QUAT 401 451 -0.0173478 -2.99093 -0.184401 0.0314 -0.00758458 -0.000728088 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.0237514 -3.77596 399.681 -9.41512 100.336 +EDGE_SE3:QUAT 402 452 0.0359814 -3.03873 -0.0784567 0.0329917 0.0104431 0.00474344 0.99939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 0.0343813 5.12433 399.631 -9.89944 100.399 +EDGE_SE3:QUAT 403 453 -0.022771 -3.00832 0.0193771 0.0315133 0.000889654 0.00911426 0.999461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 0.00099393 0.272126 399.702 -9.45103 100.29 +EDGE_SE3:QUAT 404 454 -0.0361572 -3.00766 0.0409691 0.0363416 0.00701695 0.0114257 0.999249 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.525 0.0233377 3.25531 399.585 -10.9104 100.414 +EDGE_SE3:QUAT 405 455 -0.031604 -2.83553 -0.119168 0.0290637 -0.00118171 0.0235663 0.999299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.00725056 -1.00089 399.746 -8.71057 100.2 +EDGE_SE3:QUAT 406 456 0.0127513 -3.19293 -0.0453915 0.032661 -0.00192661 -0.00683509 0.999441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 -0.00485674 -0.828451 399.679 -9.79572 100.317 +EDGE_SE3:QUAT 407 457 -0.0906149 -2.99691 -0.172306 0.033253 -0.00302253 0.00344943 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.571 -0.0107335 -1.5786 399.664 -9.96808 100.337 +EDGE_SE3:QUAT 408 458 0.121398 -3.02982 -0.363333 0.0290151 -0.00219684 -0.0457682 0.998528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 0.0013071 -0.299513 399.746 -8.72402 100.044 +EDGE_SE3:QUAT 409 459 0.00134455 -3.14766 -0.0476588 0.0291385 -0.000264554 0.00916312 0.999533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.0023198 -0.292316 399.745 -8.73747 100.247 +EDGE_SE3:QUAT 410 460 0.0447064 -3.27094 -0.141518 0.0292282 -0.00400127 -0.0166578 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.00919252 -1.70664 399.738 -8.77818 100.238 +EDGE_SE3:QUAT 411 461 -0.0889622 -2.85268 -0.0480516 0.032478 0.00407565 -0.0195689 0.999273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 0.0165456 2.41657 399.676 -9.72237 100.293 +EDGE_SE3:QUAT 412 462 0.0372867 -3.18528 -0.271924 0.0288249 -0.00224879 0.0511035 0.998275 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 -0.0135962 -2.00388 399.747 -8.62425 99.9973 +EDGE_SE3:QUAT 413 463 0.096881 -3.08444 -0.144603 0.0332555 -0.00402307 0.0200688 0.999237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0169821 -2.40927 399.661 -9.95508 100.306 +EDGE_SE3:QUAT 414 464 -0.0822471 -3.01655 -0.0870149 0.0347043 0.00601448 -0.00640304 0.999359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 0.0219453 3.1376 399.624 -10.3964 100.384 +EDGE_SE3:QUAT 415 465 0.119231 -2.87575 0.0312047 0.023821 -0.000124376 -0.0023003 0.999714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 -3.49746e-05 -0.029285 399.83 -7.14433 100.17 +EDGE_SE3:QUAT 416 466 -0.0238928 -2.89703 -0.104066 0.0231097 -0.00320486 0.0118803 0.999657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 -0.00840771 -1.76623 399.835 -6.92338 100.154 +EDGE_SE3:QUAT 417 467 0.00737793 -3.0064 -0.10457 0.0325697 -0.00488276 0.00279547 0.999454 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 -0.0163525 -2.49386 399.672 -9.7624 100.335 +EDGE_SE3:QUAT 418 468 -0.117599 -3.19109 -0.0209419 0.0294051 -4.03033e-05 -0.00665334 0.999545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 0.00103143 0.0972148 399.741 -8.81785 100.255 +EDGE_SE3:QUAT 419 469 -0.137726 -3.07157 -0.293235 0.0281108 0.000575405 0.019757 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 -0.00150697 -0.0457038 399.763 -8.43273 100.198 +EDGE_SE3:QUAT 420 470 -0.0588484 -2.98912 0.0163386 0.0231008 -0.0028931 -0.00585903 0.999712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 -0.00613205 -1.36465 399.837 -6.93169 100.162 +EDGE_SE3:QUAT 421 471 0.0588939 -3.08021 -0.274182 0.034557 0.00258301 0.0112363 0.999336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.528 0.00631725 1.05711 399.639 -10.3668 100.349 +EDGE_SE3:QUAT 422 472 0.0998706 -3.09977 -0.117523 0.0376703 0.000880442 0.0331699 0.998739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.433 -0.0060909 -0.309859 399.574 -11.301 100.316 +EDGE_SE3:QUAT 423 473 -0.245608 -3.16258 0.0298535 0.0310403 0.00606433 -0.0105514 0.999444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 0.0200676 3.22617 399.695 -9.29404 100.306 +EDGE_SE3:QUAT 424 474 -0.0366605 -3.16246 -0.275683 0.0364559 -0.00117877 0.0118172 0.999265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.472 -0.00736744 -0.846973 399.6 -10.9269 100.386 +EDGE_SE3:QUAT 425 475 -0.00977704 -3.09312 -0.100344 0.0389664 -0.00460403 0.00203995 0.999228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.421 -0.0184394 -2.34671 399.536 -11.6785 100.47 +EDGE_SE3:QUAT 426 476 -0.111029 -3.08446 -0.211274 0.0339099 0.00325955 0.0178553 0.99926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.547 0.00713962 1.26453 399.651 -10.1791 100.318 +EDGE_SE3:QUAT 427 477 -0.0108214 -3.09198 -0.0355495 0.0287222 0.0033749 0.0143897 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 0.00752642 1.43802 399.748 -8.62293 100.233 +EDGE_SE3:QUAT 428 478 -0.0573733 -3.1696 -0.106993 0.0424237 -0.0013242 0.0146826 0.998991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.286 -0.0107726 -1.0344 399.459 -12.7121 100.521 +EDGE_SE3:QUAT 429 479 0.163057 -2.92047 -0.175626 0.0289078 -0.00331251 0.00201475 0.999575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.00985925 -1.69001 399.745 -8.66715 100.258 +EDGE_SE3:QUAT 430 480 0.0446952 -3.1157 0.0497409 0.0295648 0.00321915 0.00792815 0.999526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 0.00824292 1.46766 399.734 -8.87056 100.262 +EDGE_SE3:QUAT 431 481 0.0376101 -3.07516 0.0221836 0.0308315 -0.00241341 0.00326008 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.00801078 -1.26598 399.712 -9.24335 100.288 +EDGE_SE3:QUAT 432 482 0.0519618 -3.10432 -0.0415326 0.0234449 -0.000946596 0.00594503 0.999707 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 -0.00285737 -0.556664 399.835 -7.03042 100.162 +EDGE_SE3:QUAT 433 483 0.0776679 -2.84919 -0.135489 0.0319172 0.00787977 -0.0166646 0.999321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.689 0.0264176 4.25545 399.668 -9.54277 100.326 +EDGE_SE3:QUAT 434 484 -0.117491 -2.89128 -0.0367233 0.033336 -0.00194761 0.0321924 0.998924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 -0.0130676 -1.61544 399.664 -9.98417 100.236 +EDGE_SE3:QUAT 435 485 -0.1062 -2.99011 -0.142849 0.0326438 -0.00061125 0.0100777 0.999416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.00412073 -0.502615 399.68 -9.78684 100.31 +EDGE_SE3:QUAT 436 486 -0.000317152 -2.9345 -0.204794 0.0256753 0.00299967 0.0013451 0.999665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.748 0.00753806 1.47827 399.799 -7.7007 100.204 +EDGE_SE3:QUAT 437 487 -0.0508378 -3.03232 -0.0248464 0.0396057 -0.00738322 -0.000231984 0.999188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.443 -0.02916 -3.68158 399.508 -11.8711 100.509 +EDGE_SE3:QUAT 438 488 -0.0578187 -2.9426 -0.145818 0.0324039 -0.00507076 -0.0360229 0.998813 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 -0.00975534 -1.83024 399.677 -9.75439 100.197 +EDGE_SE3:QUAT 439 489 -0.087692 -2.96877 0.0486791 0.0229426 0.00266924 0.00192177 0.999731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.798 0.00594053 1.30756 399.839 -6.88188 100.162 +EDGE_SE3:QUAT 440 490 -0.101993 -3.2531 -0.163744 0.0320852 -0.00858261 -0.0304513 0.998984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 -0.0243323 -3.69847 399.665 -9.673 100.258 +EDGE_SE3:QUAT 441 491 -0.0548397 -2.97261 -0.161954 0.0302684 0.00491596 0.00564516 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 0.0140574 2.35357 399.716 -9.08145 100.288 +EDGE_SE3:QUAT 442 492 0.0476361 -3.03631 -0.0250002 0.0299356 0.00482682 -0.00203646 0.999538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.0147139 2.44823 399.722 -8.97416 100.285 +EDGE_SE3:QUAT 443 493 0.214312 -2.99151 -0.150953 0.0324621 -0.000193565 0.0133151 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 -0.00342126 -0.35591 399.684 -9.73326 100.299 +EDGE_SE3:QUAT 444 494 -0.0656956 -3.17403 -0.0652417 0.0304439 -0.00411951 0.0213607 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.0155903 -2.44743 399.714 -9.11151 100.248 +EDGE_SE3:QUAT 445 495 -0.0713465 -2.86925 0.0338818 0.0354871 -0.000321484 -0.00446828 0.99936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.496 -1.34354e-05 -0.065458 399.622 -10.6397 100.376 +EDGE_SE3:QUAT 446 496 0.0593604 -3.02213 -0.113658 0.0349668 -0.000429568 -0.0318388 0.998881 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.512 0.00625008 0.453134 399.633 -10.4881 100.266 +EDGE_SE3:QUAT 447 497 -0.0463884 -3.06277 0.0458042 0.0239566 0.00788234 -0.0133662 0.999593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.86 0.0188151 4.13161 399.802 -7.16287 100.201 +EDGE_SE3:QUAT 448 498 0.0517956 -2.92205 -0.0539414 0.0272184 -0.00151154 0.0506068 0.998347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.010778 -1.57915 399.775 -8.15042 99.9717 +EDGE_SE3:QUAT 449 499 0.110917 -3.00957 -0.0831002 0.0318938 -0.00221014 -0.0207313 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 -0.0028994 -0.707104 399.693 -9.57308 100.264 +EDGE_SE3:QUAT 450 500 0.0434672 -2.90754 -0.0126111 0.033569 0.0100718 0.0259191 0.999049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 0.0318457 4.50709 399.625 -10.1163 100.332 +EDGE_SE3:QUAT 451 501 -0.0013868 -3.14524 -0.00917391 0.0316898 0.00602538 -0.00967881 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.652 0.020325 3.19416 399.683 -9.48968 100.32 +EDGE_SE3:QUAT 452 502 -0.275645 -3.12191 -0.0770046 0.0220932 0.00464891 0.00731103 0.999718 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.83 0.00981748 2.22657 399.845 -6.63286 100.155 +EDGE_SE3:QUAT 453 503 0.0725374 -3.00983 0.0475128 0.0334962 -0.000955901 -0.0138676 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 -8.90526e-05 -0.198801 399.663 -10.0462 100.318 +EDGE_SE3:QUAT 454 504 0.123422 -3.18604 -0.0824937 0.0309105 -0.00682284 -0.021681 0.999264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.0183718 -3.00545 399.696 -9.29817 100.267 +EDGE_SE3:QUAT 455 505 0.11624 -3.08774 -0.0372738 0.0364574 0.000512303 -0.0125861 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 0.00518311 0.53099 399.601 -10.9289 100.384 +EDGE_SE3:QUAT 456 506 0.0899581 -3.09202 -0.191797 0.0307638 0.00164767 -0.0161793 0.999394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.00798118 1.12149 399.715 -9.21973 100.261 +EDGE_SE3:QUAT 457 507 -0.0583982 -2.92281 -0.123895 0.0323118 -0.00331562 -0.0291452 0.999047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 -0.00487562 -1.09031 399.683 -9.70905 100.233 +EDGE_SE3:QUAT 458 508 -0.0224024 -3.01623 -0.00626124 0.0278733 -0.00791093 -0.0121752 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.0214123 -3.7493 399.743 -8.37701 100.259 +EDGE_SE3:QUAT 459 509 0.00568359 -3.23055 -0.0902167 0.0318592 0.00207744 0.0147256 0.999382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 0.00368139 0.756198 399.694 -9.5593 100.285 +EDGE_SE3:QUAT 460 510 0.0356975 -3.09423 -0.138503 0.0296923 0.00351844 0.00839599 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 0.00911115 1.60823 399.731 -8.90954 100.265 +EDGE_SE3:QUAT 461 511 0.00870035 -3.16357 -0.135112 0.0242937 -0.00480065 0.00174513 0.999692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.795 -0.0117915 -2.42468 399.814 -7.28387 100.193 +EDGE_SE3:QUAT 462 512 0.122157 -3.09977 0.0239496 0.0384987 -0.000356724 6.66203e-06 0.999259 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.407 -0.00137125 -0.178278 399.555 -11.5411 100.445 +EDGE_SE3:QUAT 463 513 -0.113572 -3.0456 -0.172146 0.0223116 0.00646805 0.0227025 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.844 0.0135966 2.92757 399.835 -6.72118 100.123 +EDGE_SE3:QUAT 464 514 0.0424182 -3.164 -0.146429 0.0221766 0.0109851 0.0315824 0.999195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.933 0.0272288 5.06677 399.807 -6.72008 100.123 +EDGE_SE3:QUAT 465 515 0.0409562 -3.13976 -0.0892642 0.0298382 -0.00569617 0.0489997 0.998337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0210368 -3.71681 399.716 -8.89395 100.061 +EDGE_SE3:QUAT 466 516 -0.164743 -3.22428 -0.0865446 0.036733 0.00168845 0.0134687 0.999233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.461 0.00258435 0.546369 399.594 -11.0173 100.388 +EDGE_SE3:QUAT 467 517 0.054379 -3.11355 -0.19167 0.0358405 0.00525735 -0.000206523 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 0.0188568 2.63033 399.604 -10.7443 100.405 +EDGE_SE3:QUAT 468 518 -0.106701 -3.09214 -0.220984 0.0329531 0.00201504 0.0038152 0.999448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 0.00582254 0.931127 399.673 -9.88202 100.327 +EDGE_SE3:QUAT 469 519 0.107002 -2.95947 -0.139402 0.0309278 0.00307396 0.0274034 0.999141 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.00447111 1.02639 399.71 -9.29181 100.216 +EDGE_SE3:QUAT 470 520 -0.108656 -3.03903 0.083943 0.0272416 0.00640274 0.0058434 0.999591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 0.0169814 3.10405 399.761 -8.17618 100.247 +EDGE_SE3:QUAT 471 521 -0.0784969 -2.83155 -0.0241067 0.0305341 -0.00627402 0.0313423 0.999023 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 -0.0219823 -3.70627 399.702 -9.1169 100.217 +EDGE_SE3:QUAT 472 522 0.0114856 -3.00226 -0.0845597 0.0344158 -0.00754398 0.0193457 0.999192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 -0.0281722 -4.16709 399.62 -10.2883 100.364 +EDGE_SE3:QUAT 473 523 -0.0513233 -2.92298 -0.0297458 0.0291833 -0.00525085 -0.0207884 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 -0.0125498 -2.25867 399.735 -8.77325 100.228 +EDGE_SE3:QUAT 474 524 0.0427063 -2.96872 -0.100256 0.0395075 0.0105515 -0.00251968 0.99916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.524 0.042009 5.33015 399.487 -11.8343 100.547 +EDGE_SE3:QUAT 475 525 -0.0549014 -3.09318 -0.0342945 0.0245902 -0.00502339 0.00922777 0.999642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.795 -0.0130052 -2.64653 399.808 -7.36515 100.192 +EDGE_SE3:QUAT 476 526 0.0680504 -2.99512 -0.101228 0.0343994 0.002911 0.00913794 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 0.00793841 1.26534 399.642 -10.319 100.352 +EDGE_SE3:QUAT 477 527 -0.122992 -3.14268 -0.311588 0.0351057 0.00232462 -0.0237457 0.999099 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 0.0135458 1.66038 399.627 -10.5149 100.32 +EDGE_SE3:QUAT 478 528 -0.0623314 -2.95136 0.167926 0.0364818 -0.00158562 -0.0238095 0.999049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 0.000550053 -0.270616 399.6 -10.9458 100.343 +EDGE_SE3:QUAT 479 529 -0.110363 -3.09787 0.00308389 0.0277883 0.00237572 0.00897316 0.999571 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.00527819 1.03739 399.766 -8.33756 100.227 +EDGE_SE3:QUAT 480 530 -0.171417 -3.10396 -0.143155 0.0405425 -0.00445619 -0.0169199 0.999025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.358 -0.0128703 -1.81296 399.5 -12.168 100.475 +EDGE_SE3:QUAT 481 531 0.00744409 -3.19463 0.116307 0.0222223 0.00184214 -0.00451163 0.999741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.808 0.00450476 0.980802 399.85 -6.66334 100.149 +EDGE_SE3:QUAT 482 532 0.0172885 -3.07817 -0.0402404 0.0278103 -0.00070463 -0.00643495 0.999592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 -0.000964523 -0.244711 399.768 -8.34083 100.228 +EDGE_SE3:QUAT 483 533 0.0944517 -3.24257 -0.130989 0.0332162 0.00543974 -0.0157115 0.99931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 0.020499 3.02998 399.656 -9.94178 100.331 +EDGE_SE3:QUAT 484 534 0.140157 -3.06507 -0.0512154 0.0282429 0.00388678 -0.0240454 0.999304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 0.0138757 2.34848 399.753 -8.45117 100.196 +EDGE_SE3:QUAT 485 535 0.0622585 -3.03014 -0.0791398 0.0376187 0.00326394 -0.0229047 0.999024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 0.0180019 2.14595 399.57 -11.2632 100.383 +EDGE_SE3:QUAT 486 536 0.0850827 -3.07701 -0.109627 0.0321557 -0.0018084 -0.0294559 0.999047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 0.000258354 -0.334705 399.689 -9.65376 100.224 +EDGE_SE3:QUAT 487 537 -0.174879 -3.11156 -0.0305111 0.0309593 -0.00286266 -0.0138803 0.99942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.623 -0.00632921 -1.17213 399.71 -9.29145 100.273 +EDGE_SE3:QUAT 488 538 -0.0598301 -2.9678 -0.203583 0.0279617 0.0120654 0.0260081 0.999198 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.845 0.0356892 5.59085 399.711 -8.4462 100.259 +EDGE_SE3:QUAT 489 539 -0.136908 -3.23325 -0.0968695 0.0263276 -0.00577669 -0.0169029 0.999494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.013707 -2.6191 399.78 -7.91489 100.2 +EDGE_SE3:QUAT 490 540 0.0183003 -3.15107 -0.0892686 0.0260594 -0.00633999 0.0241222 0.999349 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 -0.0176625 -3.5441 399.779 -7.78439 100.179 +EDGE_SE3:QUAT 491 541 0.144867 -3.06526 -0.156464 0.0217468 -0.00873971 -0.00509592 0.999712 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.907 -0.0192397 -4.3025 399.828 -6.53022 100.192 +EDGE_SE3:QUAT 492 542 0.0404083 -2.82931 0.0840477 0.0320599 -0.00523101 0.0175288 0.999319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 -0.0192828 -2.9498 399.679 -9.59436 100.301 +EDGE_SE3:QUAT 493 543 -0.215644 -2.96754 -0.125685 0.0295884 0.0043358 -0.0222857 0.999304 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.015694 2.56096 399.729 -8.85348 100.23 +EDGE_SE3:QUAT 494 544 0.257973 -3.25769 -0.0483693 0.0330471 -0.00258866 0.043271 0.998513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0166473 -2.14821 399.667 -9.88894 100.151 +EDGE_SE3:QUAT 495 545 0.158184 -2.9657 -0.109624 0.034273 -0.00161918 0.0301533 0.998956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.542 -0.012208 -1.42776 399.645 -10.2675 100.266 +EDGE_SE3:QUAT 496 546 -0.0478889 -3.20087 -0.0707272 0.0371213 0.000742593 0.00904769 0.99927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.449 0.000259289 0.16939 399.586 -11.1302 100.405 +EDGE_SE3:QUAT 497 547 -0.0394371 -3.09159 -0.175059 0.0284714 0.000914953 -0.00306365 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.677 0.00309175 0.509463 399.756 -8.5374 100.243 +EDGE_SE3:QUAT 498 548 -0.00543063 -3.10341 -0.177335 0.0377655 -0.00452406 -0.00408934 0.999268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.454 -0.0160219 -2.16661 399.564 -11.3248 100.44 +EDGE_SE3:QUAT 499 549 0.158279 -2.95606 -0.0763056 0.0296626 0.00523534 0.0225846 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.0123563 2.21275 399.726 -8.91882 100.228 +EDGE_SE3:QUAT 500 550 -0.163621 -3.16965 0.0545318 0.0330061 0.00628363 -0.0078054 0.999405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 0.0218244 3.2936 399.657 -9.88568 100.35 +EDGE_SE3:QUAT 501 551 -0.104354 -3.21142 -0.0373729 0.0309955 0.0021125 0.0217832 0.99928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 0.00242333 0.649973 399.71 -9.30408 100.243 +EDGE_SE3:QUAT 502 552 0.0419734 -3.15903 -0.0196529 0.0285464 -0.00382491 -0.0235531 0.999308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 -0.00746626 -1.5069 399.751 -8.57904 100.196 +EDGE_SE3:QUAT 503 553 0.102133 -2.97393 -0.12117 0.0364852 0.0105343 0.00213265 0.999276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 0.038341 5.21612 399.557 -10.9398 100.475 +EDGE_SE3:QUAT 504 554 -0.0251412 -3.15216 -0.0474008 0.0297851 -3.0813e-05 -0.0197039 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 0.00339008 0.336592 399.734 -8.93224 100.228 +EDGE_SE3:QUAT 505 555 -0.00332317 -3.05428 -0.0346111 0.0310397 0.00882095 -0.0190284 0.999298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 0.0280215 4.76107 399.678 -9.27236 100.314 +EDGE_SE3:QUAT 506 556 -0.0533068 -3.13507 -0.0539043 0.0274783 0.00282275 0.000487578 0.999618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 0.00768033 1.40242 399.77 -8.24049 100.232 +EDGE_SE3:QUAT 507 557 0.0683012 -3.15511 0.054601 0.035938 0.00648522 -0.00161748 0.999332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 0.0235775 3.27419 399.596 -10.7712 100.417 +EDGE_SE3:QUAT 508 558 -0.150612 -3.02293 -0.024401 0.034031 0.00151357 -0.0314331 0.998925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 0.01201 1.39674 399.651 -10.1953 100.253 +EDGE_SE3:QUAT 509 559 0.129548 -3.07578 -0.213948 0.0322405 -0.00620877 0.00837488 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 -0.021112 -3.26375 399.672 -9.65581 100.334 +EDGE_SE3:QUAT 510 560 0.115483 -3.05728 -0.133386 0.0324977 -0.00678184 -0.0375009 0.998745 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 -0.0160681 -2.65295 399.668 -9.79661 100.2 +EDGE_SE3:QUAT 511 561 -0.164549 -3.1017 -0.0506549 0.0328555 0.00584151 0.00141325 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 0.0189555 2.8904 399.663 -9.85217 100.347 +EDGE_SE3:QUAT 512 562 0.0121592 -3.07021 -0.0297745 0.0413241 -0.00378107 -0.0029613 0.999134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.334 -0.0146393 -1.81431 399.482 -12.3885 100.521 +EDGE_SE3:QUAT 513 563 0.00163415 -3.14105 -0.165022 0.0322997 0.00243556 -0.00111139 0.999475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.00807178 1.23819 399.685 -9.68417 100.317 +EDGE_SE3:QUAT 514 564 -0.0918992 -3.21551 -0.0462589 0.0404269 -0.00986164 0.00389356 0.999126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.478 -0.0404593 -5.0197 399.47 -12.1075 100.559 +EDGE_SE3:QUAT 515 565 -0.00941106 -2.9553 0.0309539 0.0324026 0.00252726 -0.00395483 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.59 0.00895348 1.33931 399.682 -9.71353 100.318 +EDGE_SE3:QUAT 516 566 0.0881701 -3.16325 -0.0750626 0.0355846 0.00655105 0.00473838 0.999334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.545 0.0224328 3.17103 399.603 -10.6738 100.406 +EDGE_SE3:QUAT 517 567 0.117849 -2.80609 -0.232063 0.0355389 0.0138056 -0.00825198 0.999239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 0.0484405 7.07551 399.543 -10.627 100.51 +EDGE_SE3:QUAT 518 568 0.137367 -2.90154 -0.0226107 0.0274777 0.00442166 -0.0350784 0.998997 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.0155475 2.78519 399.764 -8.21021 100.123 +EDGE_SE3:QUAT 519 569 0.15282 -2.9799 -0.0173958 0.0193714 0.00291814 -0.000742454 0.999808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.861 0.00569466 1.46725 399.884 -5.80976 100.119 +EDGE_SE3:QUAT 520 570 -0.169751 -2.95091 -0.182311 0.026482 -0.00413343 -0.0214795 0.99941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 -0.00839559 -1.72344 399.784 -7.95993 100.174 +EDGE_SE3:QUAT 521 571 0.118028 -3.16972 -0.00385608 0.0272445 -0.000635988 0.0202607 0.999423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 -0.00468088 -0.648738 399.777 -8.16827 100.183 +EDGE_SE3:QUAT 522 572 0.0744819 -3.06681 -0.10571 0.0260598 0.00615878 0.0147039 0.999533 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.0149184 2.84736 399.782 -7.83303 100.206 +EDGE_SE3:QUAT 523 573 -0.173998 -2.97492 -0.0652306 0.0268313 0.000490604 0.0271469 0.999271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.00258964 -0.19184 399.784 -8.05014 100.142 +EDGE_SE3:QUAT 524 574 -0.123564 -2.85526 -0.0244972 0.0296139 0.000375424 -0.0191288 0.999378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 0.00442961 0.527252 399.737 -8.87935 100.227 +EDGE_SE3:QUAT 525 575 0.0111203 -3.13927 -0.125059 0.0259363 0.0019589 -0.00755243 0.999633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 0.00602628 1.09633 399.796 -7.77528 100.199 +EDGE_SE3:QUAT 526 576 -0.255423 -2.9201 -0.196621 0.0264605 0.00455662 -0.03557 0.999006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.764 0.0150363 2.83902 399.78 -7.90398 100.104 +EDGE_SE3:QUAT 527 577 -0.0583655 -3.09565 -0.0726507 0.0314353 -0.000927103 0.00991211 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 -0.00483811 -0.649989 399.703 -9.42421 100.288 +EDGE_SE3:QUAT 528 578 0.0365176 -3.12017 0.0846079 0.0315251 0.00313456 0.0116546 0.99943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 0.00770456 1.34535 399.698 -9.46018 100.29 +EDGE_SE3:QUAT 529 579 0.0365424 -3.01631 -0.181254 0.026178 0.00255825 -0.0354087 0.999027 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 0.0107288 1.8328 399.791 -7.83395 100.088 +EDGE_SE3:QUAT 530 580 0.0981233 -3.08102 -0.226484 0.0374528 0.0014655 0.00479555 0.999286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.441 0.00414297 0.624101 399.578 -11.2294 100.42 +EDGE_SE3:QUAT 531 581 0.123115 -3.10015 -0.403189 0.0327305 0.00383631 -0.0231586 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 0.0165926 2.37016 399.671 -9.79646 100.282 +EDGE_SE3:QUAT 532 582 -0.0367158 -2.95233 -0.152982 0.0357139 -0.000855889 -0.0118444 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 -3.22854e-05 -0.173713 399.617 -10.7096 100.369 +EDGE_SE3:QUAT 533 583 0.0902465 -3.11587 -0.178165 0.0324835 0.000377861 -0.0197107 0.999278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 0.00534137 0.572667 399.683 -9.73901 100.278 +EDGE_SE3:QUAT 534 584 0.0440548 -2.96893 -0.0821 0.0300482 0.00214515 0.0202326 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 0.00286009 0.706696 399.728 -9.01965 100.232 +EDGE_SE3:QUAT 535 585 -0.143013 -2.9968 -0.0868078 0.0339813 0.00371064 -0.00515754 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.0136369 1.95857 399.648 -10.1843 100.354 +EDGE_SE3:QUAT 536 586 -0.0114761 -3.03959 0.00187525 0.0363719 -0.00128434 -0.0338407 0.998764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 0.00429455 0.0971584 399.602 -10.9151 100.283 +EDGE_SE3:QUAT 537 587 0.0941817 -3.30746 -0.0836066 0.0303829 0.00271483 0.0276872 0.999151 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.634 0.00327941 0.850906 399.721 -9.1268 100.203 +EDGE_SE3:QUAT 538 588 -0.0647356 -3.06441 -0.189473 0.0414061 0.00361443 -0.0182909 0.998968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.342 0.0205443 2.25818 399.479 -12.3981 100.494 +EDGE_SE3:QUAT 539 589 -0.111086 -2.93712 -0.0480663 0.0316566 -0.00262602 -0.0028143 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 -0.00776688 -1.25841 399.697 -9.49357 100.304 +EDGE_SE3:QUAT 540 590 0.174395 -2.91901 -0.381083 0.0278841 -0.00682606 0.0176014 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.762 -0.020064 -3.70484 399.747 -8.33725 100.239 +EDGE_SE3:QUAT 541 591 0.0193627 -3.01033 -0.196237 0.0292443 0.00806466 0.0445992 0.998544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 0.0194364 3.2405 399.721 -8.8435 100.092 +EDGE_SE3:QUAT 542 592 0.0930682 -2.9934 -0.291053 0.0360019 -0.00499068 -0.0143431 0.999236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.505 -0.0147187 -2.18241 399.602 -10.8077 100.383 +EDGE_SE3:QUAT 543 593 -0.133796 -3.14294 0.109997 0.0277644 0.00862086 0.00460789 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.784 0.0238481 4.23165 399.739 -8.33258 100.28 +EDGE_SE3:QUAT 544 594 0.0323602 -3.15931 -0.052984 0.0311076 -0.00588904 -0.00957592 0.999453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.652 -0.0169833 -2.76332 399.697 -9.33846 100.303 +EDGE_SE3:QUAT 545 595 0.121139 -3.06999 -0.154193 0.0293861 -0.00608704 -0.0115077 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.0165651 -2.83825 399.727 -8.82552 100.269 +EDGE_SE3:QUAT 546 596 0.0248243 -3.05119 -0.120918 0.0367738 -0.00111308 0.000535756 0.999323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.461 -0.00422593 -0.567681 399.594 -11.0245 100.407 +EDGE_SE3:QUAT 547 597 -0.0769754 -3.19866 -0.306113 0.0311638 0.00762574 0.00326692 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 0.0234658 3.74916 399.686 -9.34827 100.33 +EDGE_SE3:QUAT 548 598 0.0275225 -3.1356 0.0673245 0.0280978 0.00630474 0.00227868 0.999583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.0175123 3.11213 399.747 -8.42806 100.264 +EDGE_SE3:QUAT 549 599 -0.0222005 -3.05045 -0.216093 0.0296656 -0.00819024 0.0286397 0.999116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.0250887 -4.59986 399.706 -8.84823 100.238 +EDGE_SE3:QUAT 550 600 -0.0913171 -3.07627 -0.227804 0.0306109 0.00615686 0.0171008 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 0.0165824 2.76132 399.705 -9.19975 100.275 +EDGE_SE3:QUAT 551 601 0.217781 -3.08133 -0.0219625 0.0300768 0.00191979 0.0224288 0.999294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.00176165 0.554117 399.727 -9.0283 100.222 +EDGE_SE3:QUAT 552 602 0.138177 -2.98575 -0.21377 0.0348386 -0.0111835 -0.0212642 0.999104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.648 -0.0379522 -5.14083 399.589 -10.4907 100.397 +EDGE_SE3:QUAT 553 603 0.105881 -3.09497 -0.225522 0.0250261 -4.50247e-05 -0.0127802 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.75 0.00148576 0.169356 399.812 -7.50578 100.172 +EDGE_SE3:QUAT 554 604 0.0383596 -3.06322 -0.0970011 0.0343573 -0.00432072 -0.0117453 0.999331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.546 -0.0123621 -1.91586 399.639 -10.3111 100.351 +EDGE_SE3:QUAT 555 605 -0.0493043 -3.06466 -0.00136487 0.0370963 0.00459481 0.000800058 0.999301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 0.0168213 2.27692 399.579 -11.1214 100.427 +EDGE_SE3:QUAT 556 606 0.0645644 -2.97867 -0.150372 0.0274233 -0.00536668 -0.033781 0.999039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0107608 -2.12337 399.765 -8.26135 100.126 +EDGE_SE3:QUAT 557 607 0.0085063 -2.88327 -0.245031 0.0374753 -8.64519e-05 -0.0110076 0.999237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.438 0.00276406 0.204215 399.579 -11.2351 100.409 +EDGE_SE3:QUAT 558 608 -0.117246 -3.1119 -0.127917 0.029585 -0.00148873 0.0170705 0.999415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00725623 -1.04651 399.736 -8.86686 100.236 +EDGE_SE3:QUAT 559 609 -0.0263756 -3.24024 -0.16108 0.0345522 -0.00454819 -0.00457223 0.999382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.547 -0.0147544 -2.177 399.634 -10.3632 100.37 +EDGE_SE3:QUAT 560 610 0.167257 -3.23493 -0.0561997 0.040086 -0.00576047 0.0135837 0.999087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.412 -0.0264306 -3.20262 399.503 -11.9997 100.491 +EDGE_SE3:QUAT 561 611 -0.130666 -3.12044 -0.359361 0.030021 0.00483328 0.0221632 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.0111642 2.01466 399.721 -9.02403 100.234 +EDGE_SE3:QUAT 562 612 -0.0075968 -2.98718 0.0539465 0.0325586 -0.00060703 0.0226097 0.999214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 -0.00668254 -0.744547 399.681 -9.76043 100.268 +EDGE_SE3:QUAT 563 613 -0.0297144 -3.02826 -0.0633629 0.030892 0.00196257 0.0136752 0.999427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 0.0034972 0.726904 399.712 -9.26878 100.269 +EDGE_SE3:QUAT 564 614 -0.0219157 -3.08952 0.0546854 0.0322178 -0.00942791 -0.0204414 0.999227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0289257 -4.31382 399.655 -9.69768 100.325 +EDGE_SE3:QUAT 565 615 -0.180138 -2.92808 -0.146498 0.0348217 0.00786863 0.0060386 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 0.0265611 3.80452 399.612 -10.4482 100.401 +EDGE_SE3:QUAT 566 616 -0.0209347 -3.13195 -0.0894558 0.033717 0.00205795 -0.0491428 0.99822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.568 0.0167742 2.01884 399.655 -10.0928 100.109 +EDGE_SE3:QUAT 567 617 0.103565 -2.87903 -0.0553424 0.0315801 0.00161566 0.0119764 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 0.0027352 0.58016 399.7 -9.47337 100.286 +EDGE_SE3:QUAT 568 618 0.0717569 -3.03175 -0.147548 0.0275641 -0.00338814 0.00271596 0.999611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.00968301 -1.73788 399.767 -8.26402 100.236 +EDGE_SE3:QUAT 569 619 0.176132 -3.03593 -0.226181 0.0356332 -0.000970046 -0.00381198 0.999357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.00248504 -0.402998 399.619 -10.6839 100.38 +EDGE_SE3:QUAT 570 620 0.0262121 -3.2364 -0.31317 0.0309154 -8.56239e-05 0.00960784 0.999476 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 -0.00209701 -0.220928 399.713 -9.27015 100.278 +EDGE_SE3:QUAT 571 621 -0.0771407 -3.21892 -0.143892 0.0274778 -0.00505628 -0.0214649 0.999379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0113871 -2.17175 399.764 -8.26216 100.195 +EDGE_SE3:QUAT 572 622 -0.0191508 -2.89773 -0.192926 0.0274784 -0.0025894 -0.0437423 0.998662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.698 -0.000616635 -0.571048 399.771 -8.26568 100.037 +EDGE_SE3:QUAT 573 623 0.115673 -2.9967 -0.184285 0.0361255 0.0051508 0.0350114 0.99872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 0.0103062 1.81132 399.6 -10.8685 100.281 +EDGE_SE3:QUAT 574 624 -0.0805158 -3.0637 -0.0155647 0.0266058 0.00106748 -0.00170038 0.999644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.719 0.00307305 0.560538 399.787 -7.97852 100.213 +EDGE_SE3:QUAT 575 625 -0.149993 -3.03048 -0.0277595 0.0326008 0.00421985 0.019255 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 0.0100704 1.7308 399.675 -9.79159 100.291 +EDGE_SE3:QUAT 576 626 0.116528 -3.22838 -0.0339172 0.0292173 0.0020669 0.00510784 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 0.00519086 0.943127 399.742 -8.76353 100.256 +EDGE_SE3:QUAT 577 627 -0.110781 -3.10471 -0.199706 0.0340546 0.00222853 0.0402666 0.998606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 -0.00173626 0.289477 399.651 -10.2311 100.187 +EDGE_SE3:QUAT 578 628 0.00109741 -3.14353 -0.105799 0.0308136 -0.00571176 -0.00297903 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.0171903 -2.79866 399.702 -9.24238 100.306 +EDGE_SE3:QUAT 579 629 0.0974902 -3.11791 -0.131678 0.0290503 -0.00360321 -0.0361021 0.998919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.00473997 -1.16931 399.743 -8.73922 100.128 +EDGE_SE3:QUAT 580 630 0.00453313 -2.9714 0.0925819 0.0278203 0.00304611 0.0136976 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 0.00651271 1.29319 399.765 -8.35131 100.219 +EDGE_SE3:QUAT 581 631 -0.115355 -2.98364 0.157234 0.0314682 -0.00420061 0.02105 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.0164531 -2.4951 399.695 -9.41822 100.269 +EDGE_SE3:QUAT 582 632 0.132042 -3.11403 -0.0589675 0.0340867 -0.0063567 -0.0283752 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.567 -0.016463 -2.59294 399.637 -10.2568 100.29 +EDGE_SE3:QUAT 583 633 -0.0531079 -3.28654 -0.178329 0.0260827 0.00745846 -0.0247276 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.818 0.0198759 4.11278 399.772 -7.78477 100.188 +EDGE_SE3:QUAT 584 634 -0.102543 -2.91659 -0.169003 0.0244994 -0.005339 -0.00189435 0.999684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 -0.0129462 -2.64046 399.809 -7.34912 100.199 +EDGE_SE3:QUAT 585 635 0.0188628 -3.08291 -0.0545405 0.0283221 -0.00509916 -0.00606754 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.0137212 -2.44477 399.749 -8.49896 100.254 +EDGE_SE3:QUAT 586 636 -0.0186219 -2.91079 -0.169436 0.0326586 0.00253799 -0.0538349 0.998012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.604 0.0178334 2.31822 399.675 -9.76916 100.042 +EDGE_SE3:QUAT 587 637 0.163032 -2.88887 -0.20214 0.033975 0.00467894 -0.012593 0.999332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 0.0181823 2.59357 399.644 -10.1744 100.348 +EDGE_SE3:QUAT 588 638 -0.0349211 -2.90975 -0.0629346 0.0273719 0.00269246 0.00837976 0.999587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 0.0061945 1.20768 399.773 -8.21298 100.222 +EDGE_SE3:QUAT 589 639 -0.0784669 -2.92389 0.048557 0.032543 -0.00344607 0.0235308 0.999187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 -0.0154033 -2.17992 399.676 -9.74196 100.274 +EDGE_SE3:QUAT 590 640 -0.0971855 -3.25658 -0.121232 0.028088 0.00176191 -0.0171042 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.00747855 1.16828 399.762 -8.41735 100.211 +EDGE_SE3:QUAT 591 641 -0.0338137 -3.10458 -0.0901958 0.0245391 0.000529652 -0.0176662 0.999543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 0.00339314 0.52464 399.819 -7.35802 100.15 +EDGE_SE3:QUAT 592 642 0.0211381 -3.10805 0.117471 0.0251913 0.00617023 0.0015066 0.999662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.795 0.0154565 3.06098 399.795 -7.55616 100.216 +EDGE_SE3:QUAT 593 643 -0.0390567 -2.88846 -0.0667041 0.0327301 0.000293906 -0.000807492 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 0.00113267 0.162663 399.679 -9.81373 100.321 +EDGE_SE3:QUAT 594 644 -0.0688095 -2.9161 -0.064569 0.0266893 -0.00429679 -0.0338258 0.999062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.00729253 -1.6035 399.78 -8.03432 100.108 +EDGE_SE3:QUAT 595 645 0.104472 -3.12484 -0.116632 0.0308333 -6.72497e-05 0.0199128 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 -0.00397217 -0.401805 399.715 -9.24591 100.246 +EDGE_SE3:QUAT 596 646 -0.0754471 -3.10779 -0.122706 0.0292836 2.26744e-05 -0.0310719 0.999088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.00533655 0.556928 399.742 -8.78255 100.161 +EDGE_SE3:QUAT 597 647 -0.293249 -3.21274 -0.103374 0.0258069 0.000329027 -0.0018586 0.999665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.00109499 0.193187 399.8 -7.73938 100.2 +EDGE_SE3:QUAT 598 648 -0.0803516 -3.08883 -0.0913335 0.0357129 -0.0076504 -0.0063118 0.999313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.0263188 -3.68615 399.595 -10.7153 100.417 +EDGE_SE3:QUAT 599 649 0.135486 -3.16659 0.0217741 0.0357026 0.00513247 -0.0371454 0.998659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.552 0.0248798 3.35577 399.604 -10.6671 100.272 +EDGE_SE3:QUAT 600 650 -0.034966 -3.0843 -0.0254212 0.0328832 -0.000702116 -0.0213877 0.99923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.567 0.00232009 0.0711898 399.675 -9.86337 100.279 +EDGE_SE3:QUAT 601 651 -0.0783863 -2.89001 -0.088552 0.0263751 -0.00229653 -0.00455237 0.999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.728 -0.00545483 -1.07551 399.789 -7.91179 100.21 +EDGE_SE3:QUAT 602 652 0.0286726 -3.02008 -0.0385886 0.0257034 -0.00073646 0.0232659 0.999399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.0048828 -0.726502 399.801 -7.70569 100.145 +EDGE_SE3:QUAT 603 653 0.0625562 -3.10728 -0.0534136 0.0302448 -0.004658 -0.0046747 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 -0.0133881 -2.24238 399.717 -9.07321 100.287 +EDGE_SE3:QUAT 604 654 -0.0726515 -3.11078 -0.0699573 0.0288699 -0.00819827 0.0075254 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.0239849 -4.22726 399.722 -8.64357 100.294 +EDGE_SE3:QUAT 605 655 0.111023 -2.91284 -0.167086 0.0174673 0.000138999 -0.011382 0.999783 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.878 0.000934489 0.188743 399.908 -5.23918 100.079 +EDGE_SE3:QUAT 606 656 0.0301243 -3.10369 -0.0933881 0.031038 0.0052409 -0.00744187 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 0.0172839 2.7569 399.7 -9.29851 100.304 +EDGE_SE3:QUAT 607 657 0.250933 -2.89436 -0.0721453 0.0328958 0.00172 -0.000887988 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.571 0.0058337 0.876694 399.674 -9.86302 100.327 +EDGE_SE3:QUAT 608 658 -0.142257 -2.94673 -0.100253 0.026445 0.00144315 0.0226387 0.999393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 0.000669392 0.361725 399.79 -7.93793 100.159 +EDGE_SE3:QUAT 609 659 -0.106918 -3.22448 -0.120135 0.034044 -9.93487e-05 0.00603104 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 -0.00173349 -0.172764 399.652 -10.2072 100.344 +EDGE_SE3:QUAT 610 660 -0.107243 -3.09151 -0.121869 0.0264274 0.000125552 -0.0253501 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.722 0.00383798 0.464485 399.79 -7.92564 100.146 +EDGE_SE3:QUAT 611 661 0.0576411 -2.92054 -0.0636224 0.0303698 0.00267147 0.000992614 0.999535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 0.00792974 1.31657 399.72 -9.10712 100.281 +EDGE_SE3:QUAT 612 662 0.080842 -3.10442 -0.0254554 0.0277876 -0.00334993 -0.00560111 0.999593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.00853462 -1.58045 399.764 -8.33663 100.236 +EDGE_SE3:QUAT 613 663 -0.000810475 -2.91316 -0.22155 0.0292445 -0.0058868 -0.00416006 0.999546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 -0.0167434 -2.86844 399.73 -8.77378 100.278 +EDGE_SE3:QUAT 614 664 -0.131808 -2.9568 0.0245631 0.0273852 0.00156952 0.00800001 0.999592 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 0.00311771 0.652773 399.774 -8.21503 100.22 +EDGE_SE3:QUAT 615 665 0.139337 -2.98617 -0.145113 0.0273128 0.00384152 -0.00484645 0.999608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 0.0110674 1.99895 399.77 -8.18677 100.232 +EDGE_SE3:QUAT 616 666 0.0209602 -3.14324 -0.14566 0.0282055 0.00275228 -0.0399104 0.998801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 0.0129633 2.04822 399.757 -8.43819 100.089 +EDGE_SE3:QUAT 617 667 -0.0323372 -3.03405 -0.00795233 0.0305747 0.00384426 0.000779242 0.999525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.645 0.011613 1.90632 399.714 -9.16838 100.291 +EDGE_SE3:QUAT 618 668 0.0625432 -2.96391 -0.249299 0.0246347 -0.00218503 0.00919241 0.999652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 -0.00639488 -1.2277 399.816 -7.38416 100.178 +EDGE_SE3:QUAT 619 669 -0.00919857 -3.20073 -0.110496 0.0344318 -0.00296489 0.0400092 0.998601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.556 -0.0182356 -2.30474 399.639 -10.3019 100.208 +EDGE_SE3:QUAT 620 670 0.142185 -3.16806 -0.183042 0.0312497 -0.00162012 -0.00608178 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 -0.00388767 -0.695329 399.706 -9.37231 100.291 +EDGE_SE3:QUAT 621 671 -0.0838522 -3.06195 -0.104522 0.0261174 -0.00439773 -0.0420097 0.998766 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 -0.00649794 -1.53626 399.789 -7.87165 100.037 +EDGE_SE3:QUAT 622 672 -0.146327 -3.08104 -0.203005 0.0239876 -0.0010889 0.0101303 0.99966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 -0.00374113 -0.689892 399.827 -7.19208 100.164 +EDGE_SE3:QUAT 623 673 0.129303 -3.00686 -0.0162339 0.0385413 0.00355413 -0.0199802 0.999051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.433 0.0189051 2.23599 399.548 -11.5398 100.418 +EDGE_SE3:QUAT 624 674 -0.120919 -2.88785 -0.0695128 0.032347 0.000357774 -0.00608402 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 0.00242379 0.29675 399.686 -9.69863 100.31 +EDGE_SE3:QUAT 625 675 0.108143 -3.22631 -0.0574474 0.0281033 -0.00116268 -0.0155296 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 -0.000822752 -0.31903 399.763 -8.4316 100.213 +EDGE_SE3:QUAT 626 676 0.00855134 -3.03155 0.0720902 0.0321681 -0.00108422 0.00207771 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.588 -0.00390547 -0.581695 399.689 -9.64495 100.311 +EDGE_SE3:QUAT 627 677 -0.0407317 -2.99311 -0.0451831 0.0356167 0.00143643 -0.0108592 0.999305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.498 0.00778954 0.949285 399.618 -10.6752 100.371 +EDGE_SE3:QUAT 628 678 0.153689 -3.03586 -0.119724 0.034243 0.00346338 -0.0101991 0.999355 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 0.013958 1.93927 399.643 -10.2596 100.351 +EDGE_SE3:QUAT 629 679 -0.0667627 -3.17025 -0.0865129 0.0196965 -0.000563607 0.00406932 0.999798 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.845 -0.00142183 -0.329786 399.883 -5.90736 100.115 +EDGE_SE3:QUAT 630 680 0.240884 -2.94906 -0.146747 0.0256076 -0.00062399 -0.0352847 0.999049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 0.0030246 0.230329 399.803 -7.68575 100.072 +EDGE_SE3:QUAT 631 681 -0.0322977 -3.11386 -0.256465 0.0300381 0.00328361 -0.00787627 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 0.0110933 1.78238 399.725 -9.00202 100.273 +EDGE_SE3:QUAT 632 682 0.0458059 -3.10663 -0.230961 0.0271462 0.00326653 0.00908947 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 0.00766416 1.48409 399.775 -8.14673 100.219 +EDGE_SE3:QUAT 633 683 0.105267 -3.06434 -0.0411372 0.0250841 -0.00408689 -0.0278482 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.00728506 -1.62197 399.806 -7.5464 100.12 +EDGE_SE3:QUAT 634 684 0.0417394 -2.95678 -0.00337082 0.024029 0.00667945 0.0195743 0.999497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.816 0.0151261 3.05507 399.81 -7.23255 100.162 +EDGE_SE3:QUAT 635 685 0.100183 -3.00557 -0.0809461 0.0304932 -0.00919989 -0.00145841 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.736 -0.0280384 -4.57074 399.687 -9.14449 100.337 +EDGE_SE3:QUAT 636 686 0.0405188 -2.94075 -0.0807655 0.0220676 0.00479858 0.0152206 0.999629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.83 0.00963991 2.19639 399.845 -6.63321 100.137 +EDGE_SE3:QUAT 637 687 0.0948729 -3.1515 -0.0340898 0.029975 0.00526823 0.00784361 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.0147219 2.49102 399.72 -8.99626 100.281 +EDGE_SE3:QUAT 638 688 -0.0413858 -3.18189 -0.024737 0.0278228 0.000787073 0.0123082 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 0.000285111 0.187803 399.768 -8.34576 100.217 +EDGE_SE3:QUAT 639 689 0.116434 -3.10073 -0.158501 0.0296944 -0.00785639 0.00479762 0.999517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.731 -0.0236376 -4.01137 399.71 -8.89547 100.307 +EDGE_SE3:QUAT 640 690 0.0824377 -3.11335 -0.148959 0.029208 -0.00444806 0.0212923 0.999337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.0156067 -2.59468 399.735 -8.73981 100.228 +EDGE_SE3:QUAT 641 691 -0.104628 -3.00161 -0.103736 0.0316619 -0.00902138 -0.0145049 0.999353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 -0.0275609 -4.2313 399.668 -9.51855 100.332 +EDGE_SE3:QUAT 642 692 -0.0255222 -3.10173 0.0753851 0.0206509 -0.00904905 0.0244653 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.953 -0.016765 -4.82507 399.838 -6.1489 100.131 +EDGE_SE3:QUAT 643 693 0.134381 -2.95403 -0.107628 0.0357666 -0.00170643 0.0118824 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 -0.0090262 -1.10702 399.615 -10.7192 100.373 +EDGE_SE3:QUAT 644 694 -0.0927595 -3.01516 -0.0966376 0.0302915 -0.0031246 0.00695863 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.648 -0.0105872 -1.68745 399.721 -9.07875 100.278 +EDGE_SE3:QUAT 645 695 0.0650283 -3.09518 0.00256764 0.0353347 0.00307909 0.0101772 0.999319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.509 0.00844655 1.32203 399.622 -10.6 100.37 +EDGE_SE3:QUAT 646 696 0.06834 -3.10697 -0.0879081 0.0325515 0.00350126 0.00252998 0.999461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.0108949 1.69962 399.677 -9.76178 100.325 +EDGE_SE3:QUAT 647 697 -0.104393 -3.08199 -0.114826 0.0324502 0.00428144 -0.0234559 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.017712 2.59437 399.675 -9.7101 100.278 +EDGE_SE3:QUAT 648 698 -0.138608 -2.95232 -0.11823 0.0283599 -0.0041115 -0.0133122 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.00983217 -1.82756 399.753 -8.51547 100.234 +EDGE_SE3:QUAT 649 699 -0.257695 -2.99525 -0.149945 0.0232149 0.00444998 -0.0120459 0.999648 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.815 0.0111361 2.39157 399.83 -6.95165 100.163 +EDGE_SE3:QUAT 650 700 -0.0894419 -3.19973 0.0132695 0.035726 0.000621574 -0.0125476 0.999283 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.491 0.00538817 0.579227 399.617 -10.7096 100.368 +EDGE_SE3:QUAT 651 701 -0.0248016 -2.97752 -0.110349 0.0352361 0.0129709 0.00201653 0.999293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 0.0459794 6.43928 399.561 -10.5651 100.489 +EDGE_SE3:QUAT 652 702 0.0620787 -3.20143 -0.312803 0.0277604 -0.00700876 0.0103919 0.999536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 -0.0200655 -3.67538 399.748 -8.30939 100.257 +EDGE_SE3:QUAT 653 703 0.0826487 -3.06463 0.0273676 0.0306551 -0.00717686 -0.0131881 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.0205896 -3.34283 399.699 -9.21034 100.297 +EDGE_SE3:QUAT 654 704 -0.0814438 -3.13962 -0.148475 0.0282843 -0.00603484 -0.00231542 0.999579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 -0.0168422 -2.97631 399.746 -8.48394 100.264 +EDGE_SE3:QUAT 655 705 0.0662315 -3.07415 -0.103446 0.0267797 0.00544311 0.00164947 0.999625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.751 0.0144213 2.69356 399.773 -8.03225 100.235 +EDGE_SE3:QUAT 656 706 -0.000459968 -3.02377 -0.110942 0.0350375 0.00338286 -0.0240757 0.99909 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 0.016937 2.19469 399.626 -10.489 100.322 +EDGE_SE3:QUAT 657 707 0.0770635 -2.9474 -0.049141 0.0296383 0.00276724 0.0161466 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 0.00549747 1.09519 399.734 -8.89679 100.241 +EDGE_SE3:QUAT 658 708 -0.0495085 -3.27615 -0.147046 0.0309798 0.00283477 0.027445 0.999139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 0.00367381 0.905348 399.71 -9.30613 100.216 +EDGE_SE3:QUAT 659 709 0.0033146 -2.96458 -0.00803129 0.0312408 -0.00215756 -0.0111184 0.999448 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.613 -0.00462117 -0.869384 399.706 -9.37259 100.283 +EDGE_SE3:QUAT 660 710 0.243191 -3.20723 -0.0870602 0.036152 -0.00117343 -0.0274648 0.998968 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.477 0.0029464 0.00970727 399.607 -10.8463 100.317 +EDGE_SE3:QUAT 661 711 0.204564 -3.00899 -0.185351 0.0353767 -0.000249548 0.020571 0.999162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.501 -0.00598643 -0.560987 399.624 -10.6061 100.334 +EDGE_SE3:QUAT 662 712 -0.0463396 -2.9789 -0.0567237 0.0325237 0.00508524 -0.00697004 0.999434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0176399 2.67634 399.672 -9.74425 100.332 +EDGE_SE3:QUAT 663 713 -0.0362462 -3.02737 0.0813519 0.0240482 0.000992548 -0.0204837 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 0.00466627 0.791297 399.826 -7.20877 100.133 +EDGE_SE3:QUAT 664 714 -0.0650279 -2.9986 -0.160333 0.0275876 0.00413214 -0.0132688 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 0.0129198 2.28407 399.764 -8.26198 100.225 +EDGE_SE3:QUAT 665 715 0.131739 -3.09642 -0.071034 0.0379932 0.00328125 0.0137918 0.999177 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.431 0.00863438 1.32401 399.563 -11.3989 100.42 +EDGE_SE3:QUAT 666 716 0.0797012 -2.97075 -0.0576583 0.036988 -0.00402475 0.0139574 0.99921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.482 -0.0181465 -2.31934 399.582 -11.0774 100.405 +EDGE_SE3:QUAT 667 717 -0.00621292 -3.17685 -0.199553 0.0285268 -0.00345454 0.0279106 0.999197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 -0.0134464 -2.20244 399.75 -8.53599 100.178 +EDGE_SE3:QUAT 668 718 0.060683 -3.00908 -0.180527 0.0209611 0.00166775 0.00565878 0.999763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.827 0.00301985 0.762368 399.867 -6.28884 100.13 +EDGE_SE3:QUAT 669 719 -0.0318945 -3.14906 0.0363823 0.0331045 -0.00229844 0.00081615 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 -0.00776462 -1.16431 399.669 -9.9254 100.332 +EDGE_SE3:QUAT 670 720 0.178589 -3.10867 0.0191606 0.0370605 0.00548113 -0.0140924 0.999199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.5 0.0232278 3.05033 399.575 -11.0944 100.417 +EDGE_SE3:QUAT 671 721 -0.0155655 -3.08082 -0.0531484 0.0327455 -0.00481853 -0.0455087 0.998415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 -0.00679536 -1.50926 399.671 -9.86544 100.124 +EDGE_SE3:QUAT 672 722 0.150353 -3.0813 -0.0456873 0.0435547 -0.00040571 0.0117757 0.998982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.243 -0.00620423 -0.51001 399.431 -13.0533 100.556 +EDGE_SE3:QUAT 673 723 0.0097035 -3.05826 -0.0986314 0.0340837 0.00731737 -0.00392148 0.999385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 0.0254539 3.73572 399.63 -10.212 100.386 +EDGE_SE3:QUAT 674 724 -0.0599824 -3.06906 -0.221878 0.0285712 0.00236995 -0.00761308 0.99956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.683 0.00791122 1.31455 399.753 -8.56418 100.244 +EDGE_SE3:QUAT 675 725 0.0611193 -2.84611 -0.118206 0.0366446 -0.00739857 0.000116906 0.999301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.534 -0.0271152 -3.69809 399.575 -10.9843 100.441 +EDGE_SE3:QUAT 676 726 0.0710463 -2.91241 -0.208907 0.0264775 0.00187251 0.0228339 0.999387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 0.00180878 0.572623 399.789 -7.94968 100.16 +EDGE_SE3:QUAT 677 727 0.0518681 -2.99773 -0.150974 0.029414 0.00644532 0.0114937 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 0.0177233 3.01734 399.725 -8.83457 100.273 +EDGE_SE3:QUAT 678 728 -0.225372 -3.01335 -0.0491786 0.0252842 0.00101017 0.0150783 0.999566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 0.000632657 0.276009 399.808 -7.58617 100.169 +EDGE_SE3:QUAT 679 729 -0.012386 -3.14058 -0.147946 0.0307196 -0.00396486 0.0164801 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 -0.0146702 -2.28409 399.71 -9.19841 100.27 +EDGE_SE3:QUAT 680 730 0.127501 -3.23616 -0.146851 0.0428755 -0.00122748 -0.0212289 0.998854 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.264 0.00255476 -0.0667714 399.448 -12.857 100.507 +EDGE_SE3:QUAT 681 731 -0.0608466 -3.12941 -0.124451 0.0358816 0.00293555 0.0063647 0.999331 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.494 0.00895307 1.32909 399.611 -10.7612 100.387 +EDGE_SE3:QUAT 682 732 0.0172322 -3.23209 -0.0754052 0.0252609 0.00163541 0.0357969 0.999038 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.000419223 0.274083 399.808 -7.58918 100.064 +EDGE_SE3:QUAT 683 733 -0.159021 -3.05302 0.0570758 0.0396891 -0.00560867 -0.0254069 0.998873 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.392 -0.0151198 -2.19424 399.517 -11.9265 100.424 +EDGE_SE3:QUAT 684 734 -0.0431675 -3.03141 -0.165398 0.032324 -0.00117763 0.0260414 0.999137 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.00903212 -1.0927 399.685 -9.687 100.248 +EDGE_SE3:QUAT 685 735 -0.0694909 -3.00382 0.0168952 0.0259215 -0.00621347 0.00196692 0.999643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 -0.016234 -3.13587 399.783 -7.77064 100.229 +EDGE_SE3:QUAT 686 736 0.0843335 -3.03308 0.0133178 0.027293 0.00554714 -0.00308024 0.999607 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.0154184 2.82244 399.764 -8.18081 100.245 +EDGE_SE3:QUAT 687 737 -0.0155025 -3.00305 -0.0920616 0.0217454 -0.0110293 0.00277584 0.999699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.971 -0.0237212 -5.55089 399.809 -6.51396 100.227 +EDGE_SE3:QUAT 688 738 -0.0530177 -3.07663 -0.197915 0.0289673 0.00364173 -0.0167664 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.688 0.0128257 2.11048 399.742 -8.67438 100.235 +EDGE_SE3:QUAT 689 739 -0.03415 -3.04972 -0.0554636 0.0188422 -0.00800079 -0.0140076 0.999692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.934 -0.0155996 -3.84083 399.869 -5.67339 100.129 +EDGE_SE3:QUAT 690 740 -0.123281 -3.04403 -0.230141 0.0288038 0.00618177 0.0166195 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 0.0159921 2.80096 399.737 -8.65779 100.245 +EDGE_SE3:QUAT 691 741 -0.108546 -2.95644 0.104505 0.0305527 0.00164943 0.0109415 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.00302049 0.623431 399.719 -9.16529 100.269 +EDGE_SE3:QUAT 692 742 -0.02648 -2.98653 -0.00950177 0.0278708 -0.00983237 0.0113043 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.826 -0.0271206 -5.1031 399.727 -8.33382 100.292 +EDGE_SE3:QUAT 693 743 0.136399 -2.98141 -0.0754871 0.027416 -0.00634658 -0.0148328 0.999494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.743 -0.016092 -2.92691 399.759 -8.24012 100.229 +EDGE_SE3:QUAT 694 744 0.0250219 -3.03039 -0.178337 0.0319169 0.00430753 0.032428 0.998955 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 0.00769581 1.5292 399.688 -9.59958 100.209 +EDGE_SE3:QUAT 695 745 -0.0317407 -3.02702 -0.00655395 0.0210302 0.00635344 -0.026565 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.889 0.0134046 3.50918 399.85 -6.2739 100.095 +EDGE_SE3:QUAT 696 746 0.0349984 -3.07044 -0.335171 0.023199 0.00204966 0.0144976 0.999624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.788 0.00326321 0.822396 399.837 -6.96397 100.143 +EDGE_SE3:QUAT 697 747 0.0869135 -3.03999 -0.0430887 0.040234 -0.0121807 -0.0226821 0.998859 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.506 -0.046796 -5.53358 399.459 -12.1129 100.525 +EDGE_SE3:QUAT 698 748 0.081417 -3.11205 0.0585525 0.0327729 -0.00604821 0.00162034 0.999443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 -0.0200467 -3.05343 399.663 -9.82371 100.348 +EDGE_SE3:QUAT 699 749 0.0472414 -3.27667 -0.0135453 0.0269899 0.00618427 -0.0173912 0.999465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.0178253 3.37139 399.765 -8.07202 100.219 +EDGE_SE3:QUAT 700 750 0.00143124 -3.02074 -0.130756 0.0257114 -0.00383942 -0.022864 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.747 -0.00725573 -1.56512 399.797 -7.7289 100.154 +EDGE_SE3:QUAT 701 751 -0.0646202 -3.13637 -0.221832 0.0376413 -0.00562778 -0.0131372 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.465 -0.01803 -2.51351 399.563 -11.2988 100.427 +EDGE_SE3:QUAT 702 752 0.0602422 -3.06527 0.0551907 0.0255745 -0.00773807 -0.0319801 0.999131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.794 -0.0182873 -3.37318 399.782 -7.71975 100.129 +EDGE_SE3:QUAT 703 753 0.0497318 -3.14818 -0.284565 0.0312385 0.000736099 -0.0314083 0.999018 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.00823804 0.95572 399.706 -9.36379 100.196 +EDGE_SE3:QUAT 704 754 0.200219 -3.01629 -0.164168 0.0335987 -0.00454626 0.00854459 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 -0.0168198 -2.44308 399.653 -10.0657 100.347 +EDGE_SE3:QUAT 705 755 -0.052488 -2.81056 -0.262404 0.0372059 -0.00549922 -0.0337022 0.998724 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.464 -0.0121001 -1.9917 399.575 -11.1928 100.316 +EDGE_SE3:QUAT 706 756 0.136117 -3.26935 -0.0411376 0.0348837 -0.00503133 -0.0028126 0.999375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.544 -0.0169625 -2.45425 399.625 -10.4609 100.381 +EDGE_SE3:QUAT 707 757 -0.0220964 -3.13557 -0.109377 0.0364414 0.000950986 -0.0218812 0.999096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.474 0.00913387 0.952877 399.601 -10.9218 100.353 +EDGE_SE3:QUAT 708 758 0.1715 -2.92704 -0.0953862 0.0288262 0.00638975 0.0275324 0.999185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 0.0153302 2.71458 399.736 -8.67988 100.196 +EDGE_SE3:QUAT 709 759 -0.0177704 -2.92812 -0.12304 0.0288911 0.00035555 -0.0182593 0.999416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 0.00404403 0.493987 399.749 -8.66288 100.218 +EDGE_SE3:QUAT 710 760 -0.00132276 -3.15674 -0.0104801 0.0280165 -0.0018301 0.00800678 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.00631446 -1.04892 399.763 -8.39873 100.232 +EDGE_SE3:QUAT 711 761 0.232386 -3.19802 -0.0631278 0.0255814 0.00480393 -0.00532957 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.771 0.0127468 2.48249 399.794 -7.66636 100.21 +EDGE_SE3:QUAT 712 762 0.0735347 -3.03618 -0.170271 0.0264639 -0.00415365 -0.0213536 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 -0.00846723 -1.73579 399.784 -7.9545 100.174 +EDGE_SE3:QUAT 713 763 -0.102391 -2.98661 -0.0574297 0.0256147 -0.012946 -0.014858 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.938 -0.03555 -6.24287 399.738 -7.71756 100.286 +EDGE_SE3:QUAT 714 764 0.0790525 -3.07381 0.0923594 0.021727 -0.00572137 -0.00310282 0.999743 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.852 -0.012319 -2.81931 399.845 -6.51961 100.163 +EDGE_SE3:QUAT 715 765 -0.246045 -2.94552 -0.0813163 0.0348898 0.00325296 -0.00465156 0.999375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.529 0.0123605 1.72208 399.63 -10.4573 100.371 +EDGE_SE3:QUAT 716 766 0.0421949 -3.12307 -0.00169529 0.0371374 -0.00103135 0.00794953 0.999278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.451 -0.00598491 -0.69206 399.586 -11.132 100.409 +EDGE_SE3:QUAT 717 767 -0.0764322 -2.9681 -0.186424 0.0281753 0.00816829 0.0186633 0.999395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 0.0219907 3.76523 399.737 -8.47898 100.245 +EDGE_SE3:QUAT 718 768 0.145398 -3.18209 -0.0298385 0.0305388 -0.00659315 -0.0294118 0.999079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.664 -0.016283 -2.75286 399.705 -9.19677 100.217 +EDGE_SE3:QUAT 719 769 0.228894 -3.07293 -0.122738 0.0358599 -0.00551232 -0.00829201 0.999307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.519 -0.0180038 -2.57469 399.603 -10.7596 100.398 +EDGE_SE3:QUAT 720 770 0.0141565 -3.11093 -0.065615 0.028917 -0.00322563 -0.00373836 0.99957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0087551 -1.54678 399.745 -8.6737 100.256 +EDGE_SE3:QUAT 721 771 -0.163798 -3.03062 -0.144652 0.0313939 -0.00124722 -0.0131211 0.99942 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 -0.00133718 -0.375905 399.704 -9.41705 100.279 +EDGE_SE3:QUAT 722 772 0.00167071 -3.00048 -0.203674 0.0318143 0.00355604 -0.0564513 0.997892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 0.0196379 2.8478 399.688 -9.50351 100.004 +EDGE_SE3:QUAT 723 773 -0.0744552 -3.10671 -0.261514 0.0300869 -0.000631285 -0.0217284 0.999311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 0.00203691 0.076813 399.728 -9.02545 100.224 +EDGE_SE3:QUAT 724 774 -0.0401624 -3.08972 -0.11275 0.0300997 0.00247651 0.0286787 0.999132 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.00236265 0.718692 399.726 -9.04123 100.192 +EDGE_SE3:QUAT 725 775 0.0601041 -3.05128 -0.0216824 0.0299951 -0.00565721 -0.0218414 0.999295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 -0.0139753 -2.43236 399.719 -9.01936 100.24 +EDGE_SE3:QUAT 726 776 0.0712137 -3.10376 -0.139921 0.0290697 0.00298695 0.0165721 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 0.00604872 1.20305 399.743 -8.7274 100.231 +EDGE_SE3:QUAT 727 777 0.0553983 -3.0064 -0.0140212 0.0217906 0.00123246 -0.0262577 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.815 0.00501288 0.958767 399.857 -6.52983 100.076 +EDGE_SE3:QUAT 728 778 0.10469 -2.94151 -0.0784139 0.0241437 -0.00150647 0.0122862 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 -0.00499109 -0.930686 399.824 -7.23741 100.162 +EDGE_SE3:QUAT 729 779 0.0935204 -3.05444 0.0383777 0.0298033 0.0057816 -0.0074046 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.693 0.0180566 3.02112 399.72 -8.92775 100.286 +EDGE_SE3:QUAT 730 780 0.0792262 -2.97175 -0.261219 0.0326386 0.00553466 0.00578264 0.999435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 0.0171078 2.65164 399.669 -9.79211 100.336 +EDGE_SE3:QUAT 731 781 -0.0647844 -3.19386 0.0147493 0.0386604 -0.00648279 0.0105324 0.999176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.466 -0.0272731 -3.48153 399.534 -11.5746 100.47 +EDGE_SE3:QUAT 732 782 -0.113585 -3.20825 -0.123464 0.031577 -0.00597782 -0.0310572 0.999001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.0139892 -2.39573 399.689 -9.50647 100.221 +EDGE_SE3:QUAT 733 783 -0.0380606 -3.23021 -0.0350393 0.0402363 0.00986037 -0.0093774 0.999098 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.492 0.0409658 5.15088 399.474 -12.0397 100.549 +EDGE_SE3:QUAT 734 784 -0.0532074 -2.92181 0.0252862 0.0342788 -0.00412016 -0.0087691 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -0.0122634 -1.87756 399.641 -10.2846 100.355 +EDGE_SE3:QUAT 735 785 -0.0742974 -2.96135 -0.0917263 0.0349192 -0.00718911 -0.0301432 0.99891 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.554 -0.0196792 -2.95683 399.616 -10.5134 100.303 +EDGE_SE3:QUAT 736 786 -0.0594782 -3.04182 0.169928 0.035204 -0.00451102 -0.00412531 0.999361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.528 -0.0149705 -2.16599 399.62 -10.5579 100.384 +EDGE_SE3:QUAT 737 787 -0.05792 -2.93917 -0.00708197 0.0336066 0.000128262 0.00217063 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -5.99484e-05 0.0203137 399.661 -10.0763 100.338 +EDGE_SE3:QUAT 738 788 -0.048066 -2.97112 -0.122619 0.0269596 0.00366669 0.0100895 0.999579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 0.00861383 1.66887 399.777 -8.09224 100.216 +EDGE_SE3:QUAT 739 789 -0.0804408 -3.06758 -0.195288 0.0288791 0.000544388 -0.00677399 0.99956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.00269196 0.389321 399.75 -8.65942 100.246 +EDGE_SE3:QUAT 740 790 -0.100383 -3.24976 -0.177829 0.0277397 0.0064667 -0.00457841 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.749 0.0182861 3.30775 399.752 -8.31191 100.259 +EDGE_SE3:QUAT 741 791 0.08881 -3.15537 -0.204829 0.0302828 -0.00982313 0.00265942 0.99949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.0298222 -4.95751 399.686 -9.07323 100.343 +EDGE_SE3:QUAT 742 792 -0.0426849 -3.00134 0.0248191 0.0218109 -0.00244464 -0.000934834 0.999759 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.817 -0.00524902 -1.20959 399.855 -6.54206 100.147 +EDGE_SE3:QUAT 743 793 0.136526 -3.09036 -0.312215 0.0341647 -0.00409592 -0.0285432 0.999 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.542 -0.00776604 -1.45961 399.644 -10.268 100.276 +EDGE_SE3:QUAT 744 794 0.122074 -3.13615 -0.0690339 0.0357357 0.00789796 0.00894453 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.0268409 3.75315 399.593 -10.7266 100.416 +EDGE_SE3:QUAT 745 795 -0.0408824 -3.06165 -0.180283 0.0275881 0.000991733 0.0164031 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.000242525 0.223981 399.771 -8.27691 100.202 +EDGE_SE3:QUAT 746 796 0.0291763 -3.14629 -0.121005 0.0269066 0.00497864 -0.0239507 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 0.0154674 2.87329 399.772 -8.04533 100.181 +EDGE_SE3:QUAT 747 797 0.00995621 -3.09276 -0.134331 0.0353957 -0.00610227 -0.020829 0.999138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 -0.0173911 -2.60459 399.611 -10.6375 100.354 +EDGE_SE3:QUAT 748 798 -0.229286 -2.88429 -0.0733723 0.0314195 0.00114981 0.0111842 0.999443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.0014099 0.363568 399.703 -9.42396 100.284 +EDGE_SE3:QUAT 749 799 0.0947196 -3.10909 -0.00814159 0.0370436 -0.00142244 -0.0136584 0.999219 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.452 -0.00152664 -0.406807 399.588 -11.1097 100.394 +EDGE_SE3:QUAT 750 800 0.139404 -2.95773 -0.0703432 0.02905 -0.00294307 -0.0133036 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 -0.00644329 -1.2384 399.744 -8.71928 100.24 +EDGE_SE3:QUAT 751 801 -0.18957 -3.11952 0.0212357 0.0365553 0.00332581 -0.0043358 0.999317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.482 0.0131936 1.75601 399.594 -10.9561 100.407 +EDGE_SE3:QUAT 752 802 -0.0838925 -3.13107 -0.192335 0.0315926 0.00771031 0.0141715 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 0.022852 3.58306 399.678 -9.49398 100.317 +EDGE_SE3:QUAT 753 803 0.0237125 -2.91934 -0.282738 0.0319566 -0.00073622 0.00633126 0.999469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.593 -0.00363 -0.489113 399.693 -9.5812 100.303 +EDGE_SE3:QUAT 754 804 0.0289448 -3.15941 -0.0906228 0.0224088 -0.00167119 -0.000677608 0.999747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 -0.00367686 -0.826115 399.848 -6.72113 100.153 +EDGE_SE3:QUAT 755 805 0.00110749 -3.21089 0.0477078 0.0267449 -0.000933132 0.0106029 0.999586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.00397897 -0.63632 399.785 -8.01874 100.204 +EDGE_SE3:QUAT 756 806 0.0533136 -2.97653 -0.0578557 0.0337572 -0.0120511 -0.0173919 0.999206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.0408754 -5.66799 399.603 -10.1605 100.405 +EDGE_SE3:QUAT 757 807 0.0501075 -3.12399 0.100344 0.0350654 -0.00975741 0.00996864 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 -0.0348754 -5.08443 399.592 -10.4912 100.43 +EDGE_SE3:QUAT 758 808 0.0597505 -2.93625 -0.0114413 0.0312189 -0.00403108 -0.0164638 0.999369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 -0.00971076 -1.70507 399.702 -9.3745 100.274 +EDGE_SE3:QUAT 759 809 -0.0970999 -3.08923 -0.195035 0.0237339 -0.00334839 0.0126851 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.793 -0.00906202 -1.8538 399.826 -7.10962 100.162 +EDGE_SE3:QUAT 760 810 0.192883 -3.12142 -0.0530891 0.038904 0.00311734 -0.00187322 0.999236 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.408 0.012628 1.60031 399.542 -11.6609 100.461 +EDGE_SE3:QUAT 761 811 -0.0395695 -3.06851 -0.313869 0.0337816 0.00382114 0.00893112 0.999382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.011042 1.72758 399.652 -10.1354 100.343 +EDGE_SE3:QUAT 762 812 0.0564086 -3.06752 0.0406841 0.0321953 -0.00413191 0.0109019 0.999414 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.613 -0.015145 -2.2745 399.682 -9.64428 100.313 +EDGE_SE3:QUAT 763 813 -0.0523111 -3.21446 0.161864 0.0223433 0.00532722 -0.00830689 0.999702 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.841 0.012277 2.7739 399.838 -6.69203 100.164 +EDGE_SE3:QUAT 764 814 0.0710168 -3.02492 -0.010862 0.0424365 -0.00199913 0.00435002 0.999088 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.286 -0.00998218 -1.10864 399.458 -12.7176 100.542 +EDGE_SE3:QUAT 765 815 0.0274515 -2.82089 -0.197057 0.0305119 -0.000612105 -0.0270058 0.999169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.00315958 0.18853 399.72 -9.15371 100.207 +EDGE_SE3:QUAT 766 816 -0.0747144 -3.01466 -0.0141552 0.0338408 -0.00592841 0.00117173 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.588 -0.0202367 -2.9853 399.642 -10.1441 100.368 +EDGE_SE3:QUAT 767 817 -0.167955 -2.95638 -0.0868385 0.028335 0.002935 -0.00743323 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.00936532 1.59276 399.755 -8.49258 100.242 +EDGE_SE3:QUAT 768 818 0.216837 -2.77782 -0.00104291 0.0225076 0.00395222 0.0475275 0.998608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.805 0.00471692 1.32995 399.843 -6.79061 99.9328 +EDGE_SE3:QUAT 769 819 -0.0817631 -3.05623 -0.0165462 0.0323792 0.00924174 0.0525524 0.99805 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 0.023952 3.58574 399.657 -9.80912 100.081 +EDGE_SE3:QUAT 770 820 -0.0594606 -3.01292 -0.0726309 0.0339183 0.00312238 0.00215683 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.552 0.0101097 1.51574 399.651 -10.1707 100.351 +EDGE_SE3:QUAT 771 821 0.0547593 -3.00883 -0.00264238 0.0316495 0.00356221 0.00120491 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0110424 1.7567 399.694 -9.49066 100.309 +EDGE_SE3:QUAT 772 822 0.169894 -3.15755 -0.271426 0.0320924 0.00399849 0.00725494 0.999451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.0115007 1.85773 399.685 -9.62831 100.314 +EDGE_SE3:QUAT 773 823 -0.0341699 -2.95514 0.0818555 0.0295352 -0.00338703 -0.0270519 0.999192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.00557138 -1.21194 399.735 -8.87597 100.194 +EDGE_SE3:QUAT 774 824 0.120443 -3.11704 -0.0224861 0.0290097 0.00960686 0.0229054 0.99927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 0.0272802 4.40007 399.713 -8.74226 100.257 +EDGE_SE3:QUAT 775 825 -0.000459441 -3.19053 0.0264692 0.0377648 -0.0016449 0.00442069 0.999276 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.434 -0.00742853 -0.92151 399.571 -11.3198 100.428 +EDGE_SE3:QUAT 776 826 0.039589 -3.11227 -0.1894 0.026469 0.00777671 0.0040588 0.999611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.795 0.0204598 3.82216 399.766 -7.94307 100.25 +EDGE_SE3:QUAT 777 827 0.108719 -3.0155 -0.154969 0.0337612 -0.00625872 0.0439205 0.998445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.632 -0.0262404 -4.0106 399.638 -10.0692 100.189 +EDGE_SE3:QUAT 778 828 0.08269 -3.0464 -0.0044232 0.0292287 -0.0109962 0.0159728 0.999385 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.834 -0.0311754 -5.77549 399.693 -8.72728 100.322 +EDGE_SE3:QUAT 779 829 0.0893296 -3.03656 -0.104166 0.0338444 0.0119471 0.0108874 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 0.0406503 5.74826 399.601 -10.1703 100.426 +EDGE_SE3:QUAT 780 830 -0.128343 -2.88215 -0.0714147 0.0293777 -0.00137867 0.0015237 0.999566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.00430085 -0.715653 399.74 -8.80905 100.26 +EDGE_SE3:QUAT 781 831 -0.0714586 -3.04641 -0.0191768 0.0243171 -0.00572742 -0.00879094 0.999649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 -0.0133633 -2.73402 399.81 -7.30258 100.191 +EDGE_SE3:QUAT 782 832 0.0764801 -3.00032 0.120822 0.0259119 0.00354584 0.0412243 0.998808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.736 0.00404786 1.12872 399.795 -7.80233 100.037 +EDGE_SE3:QUAT 783 833 0.0855575 -2.98796 -0.213588 0.0383861 -0.00132924 -0.0148539 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.411 -0.000725535 -0.32169 399.557 -11.5117 100.421 +EDGE_SE3:QUAT 784 834 0.221665 -3.04702 -0.297344 0.0307681 -0.00523998 -0.0186569 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.647 -0.0132814 -2.27279 399.706 -9.24567 100.265 +EDGE_SE3:QUAT 785 835 0.0742049 -2.93847 -0.161161 0.0317123 -0.000880269 0.00544747 0.999482 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.599 -0.00386995 -0.543342 399.698 -9.50797 100.299 +EDGE_SE3:QUAT 786 836 -0.151716 -3.13695 -0.203101 0.0334028 -0.00172047 -0.000548385 0.99944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.557 -0.00561519 -0.848392 399.664 -10.0154 100.337 +EDGE_SE3:QUAT 787 837 -0.0894004 -2.88441 -0.136029 0.0412407 0.00149177 0.0176994 0.998991 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.32 0.00012927 0.306862 399.489 -12.3676 100.48 +EDGE_SE3:QUAT 788 838 0.0210524 -3.00989 -0.154816 0.0289567 -0.00708795 0.00750925 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 -0.0210667 -3.67227 399.728 -8.67164 100.283 +EDGE_SE3:QUAT 789 839 -0.0140701 -3.2293 0.139781 0.0231378 -0.00734234 -0.0389208 0.998947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.833 -0.0156301 -3.12477 399.82 -6.99774 100.039 +EDGE_SE3:QUAT 790 840 -0.0565142 -3.02495 -0.025964 0.0369989 0.00905571 -0.00267269 0.999271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.562 0.0338492 4.58292 399.556 -11.0849 100.468 +EDGE_SE3:QUAT 791 841 0.0164769 -3.13911 -0.106503 0.0318319 0.0044379 0.00458071 0.999473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 0.0133301 2.12956 399.688 -9.54838 100.315 +EDGE_SE3:QUAT 792 842 0.0203868 -3.29879 -0.159645 0.0320444 -0.00019668 -0.0251874 0.999169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.59 0.00452093 0.38581 399.692 -9.61038 100.245 +EDGE_SE3:QUAT 793 843 0.0103455 -2.78627 -0.0255142 0.0387509 0.00488159 0.016273 0.999104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.42 0.0144965 2.05887 399.541 -11.6324 100.437 +EDGE_SE3:QUAT 794 844 -0.0729561 -3.07995 -0.105971 0.0284084 0.00151083 -0.00387678 0.999588 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 0.00489247 0.820925 399.757 -8.51789 100.242 +EDGE_SE3:QUAT 795 845 0.0618721 -3.06492 0.0399359 0.0353633 0.000270339 -0.00986227 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.5 0.00341127 0.34417 399.625 -10.602 100.366 +EDGE_SE3:QUAT 796 846 -0.0485375 -2.99825 -0.180241 0.0310833 -0.0018838 0.0401377 0.998709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 -0.0128377 -1.68774 399.707 -9.30759 100.135 +EDGE_SE3:QUAT 797 847 -0.124664 -3.00604 -0.0641998 0.0237917 -0.00394617 0.0628379 0.997732 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.0129858 -2.86116 399.821 -7.08982 99.7946 +EDGE_SE3:QUAT 798 848 0.0205685 -2.96612 0.0694419 0.0385091 0.00277072 0.01424 0.999153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.412 0.00653814 1.05443 399.553 -11.5523 100.428 +EDGE_SE3:QUAT 799 849 0.0676333 -3.01993 -0.238978 0.029998 -0.00257637 -0.00625508 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.647 -0.00665395 -1.17457 399.728 -8.9985 100.27 +EDGE_SE3:QUAT 800 850 0.0754936 -3.06356 -0.116271 0.0326217 0.00426101 -0.0254399 0.999135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.018074 2.62518 399.672 -9.76002 100.272 +EDGE_SE3:QUAT 801 851 0.052372 -3.12787 -0.0102487 0.0321692 -0.00189453 0.00638387 0.99946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 -0.00735204 -1.06954 399.688 -9.6433 100.309 +EDGE_SE3:QUAT 802 852 0.0471629 -3.07179 0.25904 0.0340569 0.0062178 -0.00651356 0.999379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.0221827 3.23908 399.636 -10.2021 100.372 +EDGE_SE3:QUAT 803 853 -0.0385874 -3.096 -0.1376 0.0335226 0.00571624 0.00919529 0.999379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 0.0175504 2.67038 399.65 -10.0611 100.349 +EDGE_SE3:QUAT 804 854 -0.0372246 -3.02773 -0.294749 0.0327473 -0.00599666 -0.00760938 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 -0.0184347 -2.84612 399.665 -9.82734 100.339 +EDGE_SE3:QUAT 805 855 0.152984 -3.14281 0.0157709 0.0328846 -0.0022123 -0.027122 0.999089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.568 -0.00146661 -0.569526 399.674 -9.87321 100.253 +EDGE_SE3:QUAT 806 856 -0.0951268 -3.23544 -0.042613 0.0250731 -0.00135622 -0.0203501 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.749 -0.000860483 -0.371435 399.811 -7.52559 100.148 +EDGE_SE3:QUAT 807 857 0.0551192 -3.09255 -0.114165 0.0212932 0.0042697 0.0200005 0.999564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.836 0.00779218 1.87783 399.857 -6.40379 100.107 +EDGE_SE3:QUAT 808 858 0.00516526 -3.17746 -0.10912 0.0331635 0.00535477 0.0102553 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.0159364 2.47069 399.659 -9.95412 100.337 +EDGE_SE3:QUAT 809 859 -0.0471174 -3.05994 -0.0632384 0.0234536 -0.00271402 0.0269556 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 -0.00876249 -1.7347 399.831 -7.02015 100.1 +EDGE_SE3:QUAT 810 860 0.0273089 -3.13088 -0.0920744 0.023437 0.0105072 0.00308688 0.999665 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.921 0.0249643 5.20949 399.791 -7.03375 100.24 +EDGE_SE3:QUAT 811 861 0.251966 -3.12255 -0.0955193 0.0338221 0.00122707 -0.0243538 0.99913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.549 0.00951181 1.10653 399.656 -10.1357 100.287 +EDGE_SE3:QUAT 812 862 0.0608597 -3.08813 -0.138249 0.0338218 0.00546911 0.0300741 0.99896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 0.0126004 2.11971 399.647 -10.1747 100.268 +EDGE_SE3:QUAT 813 863 -0.109336 -3.20256 -0.0661604 0.0312429 -0.00727471 0.0179074 0.999325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.693 -0.0242307 -3.96961 399.684 -9.3413 100.303 +EDGE_SE3:QUAT 814 864 0.0767307 -2.82207 0.0408218 0.0337159 0.00433669 0.0210451 0.9992 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 0.0102863 1.73981 399.653 -10.1277 100.307 +EDGE_SE3:QUAT 815 865 0.174826 -3.06884 -0.244626 0.0302072 -0.000638287 0.0206967 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.00563504 -0.693711 399.726 -9.05598 100.232 +EDGE_SE3:QUAT 816 866 -0.00499317 -2.98111 -0.153201 0.0220158 0.00106531 -0.0119617 0.999685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 0.00346301 0.690336 399.854 -6.60071 100.132 +EDGE_SE3:QUAT 817 867 0.00560511 -3.01963 -0.252672 0.0325073 -0.00535781 0.0109822 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 -0.0190699 -2.89055 399.671 -9.73467 100.327 +EDGE_SE3:QUAT 818 868 -0.297951 -3.0727 0.0959597 0.0322616 0.00163404 -0.0164612 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.0085411 1.13458 399.686 -9.66839 100.288 +EDGE_SE3:QUAT 819 869 -0.0823634 -3.12234 -0.127509 0.0271202 0.000120917 -0.0202081 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 0.0032804 0.3891 399.779 -8.13312 100.18 +EDGE_SE3:QUAT 820 870 -0.0146496 -2.90021 -0.12713 0.0323363 0.00648082 0.0112963 0.999392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.0193279 3.01825 399.67 -9.70977 100.328 +EDGE_SE3:QUAT 821 871 -0.102696 -3.03492 0.0019022 0.0307433 -0.007973 0.00817631 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.0250748 -4.13467 399.69 -9.20415 100.324 +EDGE_SE3:QUAT 822 872 -0.0623595 -3.14125 -0.152182 0.0331626 -0.00361252 -0.0342827 0.998855 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.565 -0.00475226 -1.12094 399.666 -9.96989 100.218 +EDGE_SE3:QUAT 823 873 0.206902 -2.83793 -0.265399 0.0269471 -0.00543587 -0.00390655 0.999614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 -0.0142738 -2.65323 399.771 -8.08489 100.236 +EDGE_SE3:QUAT 824 874 0.00242097 -2.98718 0.0651186 0.0354909 0.00380419 0.000486738 0.999363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.515 0.0133647 1.88967 399.616 -10.6406 100.388 +EDGE_SE3:QUAT 825 875 -0.140471 -3.19624 -0.290119 0.0328414 -0.000589365 -0.0321247 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 0.00497926 0.338445 399.676 -9.85256 100.221 +EDGE_SE3:QUAT 826 876 0.0134897 -2.98252 -0.123038 0.0272202 -0.0108234 -0.071068 0.997041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.786 -0.0284438 -4.22568 399.739 -8.32276 99.7765 +EDGE_SE3:QUAT 827 877 -0.0057657 -2.98519 -0.0225819 0.0322873 0.0104366 0.0101336 0.999373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 0.0334882 5.01839 399.645 -9.69996 100.375 +EDGE_SE3:QUAT 828 878 -0.00118392 -3.043 -0.0397329 0.0332473 -0.00595122 -0.0216117 0.999196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0160131 -2.54068 399.656 -9.99451 100.305 +EDGE_SE3:QUAT 829 879 -0.0541385 -3.04666 -0.135317 0.0244652 0.00476034 -0.00463195 0.999679 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 0.0119986 2.44703 399.811 -7.33255 100.194 +EDGE_SE3:QUAT 830 880 -0.0395402 -3.13943 -0.0582472 0.0242851 0.00622108 0.0244321 0.999387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 0.0135816 2.7516 399.809 -7.31393 100.14 +EDGE_SE3:QUAT 831 881 -0.162072 -3.05012 -0.105102 0.0326 -0.000118549 0.00180367 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.000768709 -0.0944847 399.681 -9.77476 100.319 +EDGE_SE3:QUAT 832 882 -0.0389838 -3.2889 -0.060577 0.0393243 9.01597e-06 0.0297996 0.998782 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.384 -0.00908967 -0.698048 399.536 -11.7899 100.376 +EDGE_SE3:QUAT 833 883 -0.02885 -3.05762 -0.0613176 0.0284384 0.00370099 -0.00923105 0.999546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.698 0.0117429 2.00659 399.751 -8.52101 100.245 +EDGE_SE3:QUAT 834 884 -0.0767035 -2.91371 -0.0139103 0.026849 0.00328734 0.00377288 0.999627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 0.00834133 1.58187 399.78 -8.05409 100.222 +EDGE_SE3:QUAT 835 885 0.145044 -3.18457 -0.0862953 0.0322267 0.00160606 0.0304885 0.999014 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.584 -0.00115369 0.212468 399.688 -9.67427 100.219 +EDGE_SE3:QUAT 836 886 0.0105162 -2.94827 -0.0144536 0.0317165 0.00195187 -0.0133579 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.00872539 1.22902 399.696 -9.50511 100.288 +EDGE_SE3:QUAT 837 887 -0.0145459 -2.98616 -0.070004 0.0273267 -0.000470372 -0.0203753 0.999419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 0.00175843 0.0990052 399.776 -8.19743 100.183 +EDGE_SE3:QUAT 838 888 0.120328 -3.01565 -0.175568 0.0287533 0.00442132 0.022828 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.00948166 1.81439 399.745 -8.64307 100.206 +EDGE_SE3:QUAT 839 889 -0.00527073 -2.89964 -0.166186 0.0361366 -0.00915856 0.0164869 0.999169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 -0.0345865 -4.93187 399.573 -10.8016 100.43 +EDGE_SE3:QUAT 840 890 -0.0661851 -3.09684 -0.143534 0.0266564 0.00396021 0.0233886 0.999363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.728 0.00766967 1.60399 399.781 -8.01311 100.167 +EDGE_SE3:QUAT 841 891 0.0175324 -3.23279 -0.175266 0.02338 -0.00176912 -0.0150972 0.999611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.783 -0.00253307 -0.672216 399.835 -7.01767 100.143 +EDGE_SE3:QUAT 842 892 -0.0641623 -3.1783 0.0883321 0.0289682 -0.000652327 0.0346077 0.998981 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 -0.00750318 -0.926689 399.747 -8.68397 100.134 +EDGE_SE3:QUAT 843 893 -0.0394914 -3.00401 -0.104158 0.03108 0.000726113 -0.00109436 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 0.00246263 0.383143 399.71 -9.31933 100.29 +EDGE_SE3:QUAT 844 894 0.0570183 -3.00372 -0.274852 0.0368946 0.00450589 0.00924721 0.999266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.477 0.0143557 2.04551 399.584 -11.0689 100.412 +EDGE_SE3:QUAT 845 895 -0.0380615 -3.10552 -0.140992 0.0319006 -0.00124386 -0.00871873 0.999452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 -0.0022 -0.454501 399.694 -9.56756 100.298 +EDGE_SE3:QUAT 846 896 -0.0796676 -2.87112 -0.0243779 0.0322144 0.000698349 -0.000291445 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 0.00230526 0.35448 399.688 -9.65924 100.312 +EDGE_SE3:QUAT 847 897 -0.0672669 -2.86321 0.117066 0.0270885 -0.00502777 -0.000361701 0.99962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.0135758 -2.50657 399.77 -8.12343 100.238 +EDGE_SE3:QUAT 848 898 0.106736 -3.17697 -0.00982482 0.0315978 -0.00263487 0.00460031 0.999487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 -0.00916511 -1.40345 399.698 -9.47203 100.303 +EDGE_SE3:QUAT 849 899 -0.123366 -3.07337 -0.0261452 0.0301254 -0.00430687 0.0144589 0.999432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.0149907 -2.41274 399.72 -9.02087 100.267 +EDGE_SE3:QUAT 850 900 0.0514619 -3.01406 -0.00618753 0.0393571 -0.000587274 0.00149876 0.999224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.381 -0.00276703 -0.328601 399.535 -11.7978 100.465 +EDGE_SE3:QUAT 851 901 0.129484 -2.98772 -0.107677 0.0444215 0.00599096 0.0126395 0.998915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.246 0.0222028 2.65331 399.395 -13.3278 100.597 +EDGE_SE3:QUAT 852 902 0.186296 -3.01508 -0.0508652 0.0269073 -0.0019112 -0.0152649 0.99952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 -0.00298356 -0.708417 399.782 -8.07537 100.196 +EDGE_SE3:QUAT 853 903 -0.0617121 -2.92871 -0.187727 0.0313569 -0.00767594 -0.00145671 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 -0.0239407 -3.80793 399.682 -9.40332 100.336 +EDGE_SE3:QUAT 854 904 0.0657111 -2.91251 -0.153895 0.0296248 -0.00349899 0.0190861 0.999373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.0131205 -2.0868 399.731 -8.87034 100.238 +EDGE_SE3:QUAT 855 905 0.0576527 -2.9949 -0.0201603 0.0321222 -0.00233426 -0.0122762 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 -0.00503045 -0.929386 399.689 -9.63758 100.297 +EDGE_SE3:QUAT 856 906 -0.072813 -3.03136 -0.135348 0.0392638 0.000653508 -0.0204406 0.99902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.387 0.00877002 0.80742 399.537 -11.7681 100.422 +EDGE_SE3:QUAT 857 907 -0.0950345 -3.13145 -0.114097 0.0308644 0.00288351 -0.0199486 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.637 0.0122317 1.80936 399.71 -9.24371 100.254 +EDGE_SE3:QUAT 858 908 -0.0824084 -2.95155 -0.0565634 0.0277907 0.00557625 -0.0420361 0.998714 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 0.0184406 3.4828 399.753 -8.28853 100.086 +EDGE_SE3:QUAT 859 909 0.135732 -3.14951 -0.13595 0.0313399 0.00856752 0.00103406 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 0.0268039 4.26161 399.676 -9.39743 100.346 +EDGE_SE3:QUAT 860 910 0.0645128 -3.09717 -0.0901706 0.0342532 0.00793979 0.00795207 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.605 0.0261587 3.80284 399.624 -10.2812 100.387 +EDGE_SE3:QUAT 861 911 0.133169 -3.11375 -0.179508 0.0281818 0.00286265 0.00315536 0.999594 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.00759923 1.37698 399.759 -8.45285 100.243 +EDGE_SE3:QUAT 862 912 0.208141 -3.06997 -0.275004 0.034787 -0.00218099 0.0131386 0.999306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.526 -0.0105788 -1.36328 399.635 -10.4242 100.35 +EDGE_SE3:QUAT 863 913 0.0228452 -3.08999 -0.161828 0.0379468 0.000733697 0.00189402 0.999278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.425 0.00223255 0.32327 399.568 -11.3761 100.432 +EDGE_SE3:QUAT 864 914 -0.173054 -3.13543 -0.116261 0.0266844 0.00662859 -0.0102718 0.999569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 0.0182711 3.47689 399.768 -7.98805 100.236 +EDGE_SE3:QUAT 865 915 -0.0217807 -2.9891 -0.128035 0.0378582 -0.00820531 -0.0299487 0.998801 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.483 -0.025029 -3.4147 399.546 -11.3988 100.377 +EDGE_SE3:QUAT 866 916 -0.1345 -3.07454 -0.15849 0.0335014 0.00670704 -0.0305344 0.99895 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.0259618 3.96168 399.642 -10.0039 100.284 +EDGE_SE3:QUAT 867 917 0.022569 -3.07268 -0.0394752 0.024711 -0.00182775 0.00078036 0.999693 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.00460211 -0.924951 399.815 -7.4107 100.186 +EDGE_SE3:QUAT 868 918 0.113911 -2.98425 -0.047503 0.0242279 -0.00521935 0.00473242 0.999682 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 -0.0129567 -2.6773 399.813 -7.2608 100.194 +EDGE_SE3:QUAT 869 919 0.0935929 -2.8295 -0.189479 0.0292175 0.0065044 -0.0362629 0.998894 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.0213745 3.88206 399.724 -8.71495 100.163 +EDGE_SE3:QUAT 870 920 -0.143523 -2.85812 -0.120242 0.0340662 0.000598057 -0.0229618 0.999156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 0.00727226 0.767652 399.651 -10.212 100.297 +EDGE_SE3:QUAT 871 921 -0.164815 -3.13075 -0.130331 0.027711 -0.00583928 0.00520002 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 -0.0166409 -3.00438 399.756 -8.30334 100.253 +EDGE_SE3:QUAT 872 922 0.152668 -3.13297 0.0524221 0.0306513 -0.00249478 0.0172283 0.999379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.0105781 -1.56278 399.715 -9.18271 100.258 +EDGE_SE3:QUAT 873 923 0.110593 -3.24041 -0.187065 0.0300335 0.00429492 -0.0110359 0.999479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 0.0144462 2.34448 399.721 -8.9962 100.273 +EDGE_SE3:QUAT 874 924 -0.179357 -2.99108 -0.120697 0.032276 -0.00650756 -0.00393952 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 -0.0204582 -3.17485 399.671 -9.68193 100.34 +EDGE_SE3:QUAT 875 925 0.0464449 -3.18683 -0.168479 0.0327143 0.00577097 0.0304375 0.998984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.596 0.0135238 2.28336 399.668 -9.84517 100.246 +EDGE_SE3:QUAT 876 926 -0.00381915 -3.10149 -0.0986604 0.034349 -0.0027374 0.0334889 0.998845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.552 -0.0163227 -2.05568 399.641 -10.2818 100.252 +EDGE_SE3:QUAT 877 927 0.041688 -3.21411 -0.132363 0.0371672 -0.00047375 0.0236306 0.99903 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.451 -0.00819348 -0.7631 399.585 -11.1412 100.36 +EDGE_SE3:QUAT 878 928 -0.00643717 -2.87597 -0.0149175 0.0360886 0.00563587 0.00510817 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.517 0.0192489 2.70427 399.597 -10.8245 100.409 +EDGE_SE3:QUAT 879 929 0.0588748 -3.09383 -0.188432 0.0272641 -0.000645725 -0.03006 0.999176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 0.00270801 0.169082 399.777 -8.18129 100.133 +EDGE_SE3:QUAT 880 930 -0.0138014 -3.06391 -0.170621 0.0367369 0.00314835 0.0165843 0.999182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 0.00724448 1.20653 399.592 -11.0244 100.382 +EDGE_SE3:QUAT 881 931 0.108728 -3.12562 0.0733991 0.0264488 -0.00177625 -0.0220524 0.999405 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.00165677 -0.537359 399.789 -7.94032 100.162 +EDGE_SE3:QUAT 882 932 0.0719464 -3.01479 -0.220671 0.0216186 0.00573235 0.0078662 0.999719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.852 0.0120946 2.76308 399.847 -6.49265 100.156 +EDGE_SE3:QUAT 883 933 0.0731653 -3.12337 0.036976 0.0273254 0.000709793 0.0302867 0.999167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 -0.00258467 -0.141917 399.776 -8.2001 100.132 +EDGE_SE3:QUAT 884 934 -0.0267161 -3.05159 -0.0843282 0.0254542 -8.23831e-05 -0.0336583 0.999109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 0.004108 0.472618 399.805 -7.63576 100.082 +EDGE_SE3:QUAT 885 935 0.23322 -3.1108 0.0916384 0.0322747 0.00336182 0.0182376 0.999307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.00727179 1.32584 399.684 -9.68999 100.285 +EDGE_SE3:QUAT 886 936 -0.156601 -2.97509 -0.0986761 0.0322669 -0.00706316 0.00292824 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 -0.0231272 -3.58557 399.667 -9.66967 100.347 +EDGE_SE3:QUAT 887 937 -0.0366022 -3.10577 -0.153094 0.0354271 0.011394 0.00609988 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 0.0402844 5.56312 399.573 -10.6321 100.461 +EDGE_SE3:QUAT 888 938 -0.10024 -2.92706 -0.289488 0.0307432 -0.0010417 0.00245564 0.999524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 -0.00365499 -0.565687 399.716 -9.21805 100.284 +EDGE_SE3:QUAT 889 939 0.0663865 -3.01716 0.0277817 0.0372563 0.00348321 -0.0218552 0.999061 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.472 0.0182622 2.22712 399.577 -11.1543 100.381 +EDGE_SE3:QUAT 890 940 0.0893573 -3.07206 0.0981277 0.0332146 0.00214874 -0.000480497 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.565 0.00722442 1.0829 399.667 -9.95857 100.334 +EDGE_SE3:QUAT 891 941 0.0978213 -3.04167 -0.0766208 0.0214997 0.00479764 -0.0242718 0.999463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.854 0.0113005 2.70986 399.851 -6.42529 100.099 +EDGE_SE3:QUAT 892 942 -0.00161554 -3.09857 -0.00185938 0.0365868 0.00158792 -0.00807578 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 0.00790252 0.97017 399.597 -10.9662 100.397 +EDGE_SE3:QUAT 893 943 0.0209751 -3.16323 -0.134262 0.0333036 0.00628206 0.03857 0.998681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 0.0139585 2.36374 399.654 -10.0359 100.203 +EDGE_SE3:QUAT 894 944 0.182204 -3.07618 -0.139507 0.0246316 -0.00422387 -0.000562671 0.999688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.78 -0.0103481 -2.1026 399.811 -7.3874 100.194 +EDGE_SE3:QUAT 895 945 -0.0416307 -3.08688 -0.245167 0.0338557 -0.0106473 0.012636 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 -0.0362266 -5.57649 399.609 -10.1212 100.413 +EDGE_SE3:QUAT 896 946 0.147749 -3.25451 -0.220992 0.0278022 -0.00022936 -0.0334174 0.999055 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.00449221 0.442613 399.768 -8.34051 100.121 +EDGE_SE3:QUAT 897 947 0.0477481 -2.97821 -0.220782 0.0317433 0.000862754 0.00814662 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 0.001097 0.275855 399.697 -9.51968 100.296 +EDGE_SE3:QUAT 898 948 0.0862325 -3.07872 -0.242241 0.0236406 -0.00189155 -0.0456483 0.998676 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.776 0.00060168 -0.296603 399.831 -7.10994 99.9603 +EDGE_SE3:QUAT 899 949 -0.0340798 -3.01524 -0.31136 0.0253902 -0.00463989 -0.0264423 0.999317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.00908153 -1.91457 399.799 -7.63974 100.135 +EDGE_SE3:QUAT 900 950 0.0314062 -3.20278 0.0229703 0.0203839 -0.00295985 -0.0147961 0.999678 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.842 -0.00498352 -1.29818 399.872 -6.12277 100.108 +EDGE_SE3:QUAT 901 951 0.130807 -3.07881 -0.156298 0.0303613 0.0039318 0.0260968 0.999191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 0.00754365 1.48794 399.718 -9.12553 100.216 +EDGE_SE3:QUAT 902 952 0.123132 -3.00814 -0.11484 0.0322372 -0.00378999 -0.00480112 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.601 -0.0113138 -1.80043 399.683 -9.66949 100.319 +EDGE_SE3:QUAT 903 953 -0.018327 -2.932 -0.00186501 0.028468 0.00222758 0.00610563 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 0.00538827 1.00869 399.755 -8.53962 100.242 +EDGE_SE3:QUAT 904 954 -0.049517 -2.96606 -0.111201 0.0379207 0.00716163 0.00952462 0.99921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.482 0.0251679 3.35978 399.549 -11.3805 100.455 +EDGE_SE3:QUAT 905 955 0.229266 -3.11498 -0.223046 0.0318684 0.00425379 -0.0220615 0.99924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.0170195 2.54592 399.687 -9.53708 100.273 +EDGE_SE3:QUAT 906 956 0.0738805 -2.97624 0.0149636 0.0393134 -0.00608741 -0.0246551 0.998904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.41 -0.0173679 -2.4568 399.524 -11.8154 100.422 +EDGE_SE3:QUAT 907 957 0.0781099 -2.94845 0.041319 0.0311691 0.00220408 -0.0132422 0.999424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 0.00926208 1.3485 399.706 -9.34045 100.279 +EDGE_SE3:QUAT 908 958 0.169471 -3.10141 -0.0932237 0.0397807 -0.00890327 0.0035329 0.999163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.474 -0.0360143 -4.53085 399.493 -11.9161 100.53 +EDGE_SE3:QUAT 909 959 -0.149071 -3.00445 -0.0775245 0.0284762 -0.00690107 0.00960136 0.999525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 -0.0203207 -3.61242 399.737 -8.52519 100.27 +EDGE_SE3:QUAT 910 960 -0.132917 -2.78686 -0.105742 0.0275268 0.0029337 -0.00313887 0.999612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.709 0.0084899 1.51771 399.769 -8.25289 100.233 +EDGE_SE3:QUAT 911 961 0.0432995 -3.121 0.00564701 0.0365154 -0.00016744 0.00312814 0.999328 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 -0.00144294 -0.152123 399.6 -10.9472 100.399 +EDGE_SE3:QUAT 912 962 0.0811981 -3.1013 -0.105646 0.0411843 0.00151312 -0.00757113 0.999122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.326 0.00873079 0.94236 399.49 -12.3425 100.505 +EDGE_SE3:QUAT 913 963 -0.232083 -3.11313 -0.10773 0.0284869 0.00146927 -0.00196234 0.999591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 0.00448918 0.767635 399.756 -8.54198 100.245 +EDGE_SE3:QUAT 914 964 0.030681 -2.99322 -0.0111456 0.0264529 0.00340694 -0.0155564 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 0.0107647 1.94897 399.785 -7.92253 100.196 +EDGE_SE3:QUAT 915 965 0.0777047 -3.13883 -0.0212222 0.0289629 0.000245377 -0.00490377 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.665 0.00153043 0.207785 399.748 -8.68501 100.249 +EDGE_SE3:QUAT 916 966 0.0671234 -3.21668 -0.0925357 0.0295592 0.00170979 0.0204621 0.999352 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 0.00150974 0.491151 399.737 -8.87147 100.221 +EDGE_SE3:QUAT 917 967 0.055155 -3.1811 -0.0594103 0.0286463 -0.000785089 0.0429519 0.998666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 -0.00894343 -1.12922 399.753 -8.58613 100.064 +EDGE_SE3:QUAT 918 968 -0.0307255 -3.15193 0.0216286 0.0290421 -0.00111284 -0.0220087 0.999335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 0.000479269 -0.17242 399.747 -8.71455 100.205 +EDGE_SE3:QUAT 919 969 0.0815884 -3.23011 -0.0179284 0.0232676 0.000138655 -0.0154771 0.999609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.784 0.0019898 0.285293 399.838 -6.97824 100.139 +EDGE_SE3:QUAT 920 970 0.0373945 -3.02067 -0.0581669 0.0272139 0.00678295 0.01564 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 0.0172607 3.13356 399.761 -8.18186 100.227 +EDGE_SE3:QUAT 921 971 0.0661091 -3.17381 -0.16367 0.0332384 0.00184988 -0.00988042 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.565 0.00823148 1.12093 399.667 -9.96238 100.325 +EDGE_SE3:QUAT 922 972 -0.160708 -3.05045 -0.243504 0.0311216 0.0104625 0.00762323 0.999432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 0.0325725 5.08588 399.667 -9.34555 100.358 +EDGE_SE3:QUAT 923 973 -0.117801 -3.11897 -0.245365 0.0301253 -0.00263269 0.01817 0.999377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.652 -0.0108747 -1.64324 399.724 -9.02418 100.246 +EDGE_SE3:QUAT 924 974 -0.0462526 -2.9713 -0.15525 0.0297319 0.00456473 -0.0153214 0.99943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 0.0155625 2.55355 399.726 -8.90143 100.259 +EDGE_SE3:QUAT 925 975 0.0561672 -2.96208 -0.297658 0.0280697 -0.00405644 0.0109397 0.999538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 -0.0127204 -2.21091 399.757 -8.40848 100.237 +EDGE_SE3:QUAT 926 976 0.226172 -2.94283 -0.184377 0.0435305 0.0057698 -0.00604701 0.999017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.291 0.0269484 3.03813 399.418 -13.0387 100.59 +EDGE_SE3:QUAT 927 977 -0.045037 -3.02154 -0.106196 0.0257626 0.00184256 0.0182763 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.736 0.00237225 0.638041 399.8 -7.73336 100.167 +EDGE_SE3:QUAT 928 978 -0.0921606 -3.01449 -0.144193 0.0288517 -0.00626304 0.000922813 0.999564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.719 -0.018155 -3.14558 399.735 -8.64991 100.277 +EDGE_SE3:QUAT 929 979 -0.0591735 -3.19667 -0.0879218 0.02787 0.00130967 -0.00306009 0.999606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.00410901 0.705534 399.766 -8.35691 100.233 +EDGE_SE3:QUAT 930 980 -0.00201238 -3.11049 0.0113263 0.0262119 0.00244465 -0.0103105 0.9996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 0.00767788 1.38361 399.791 -7.85583 100.201 +EDGE_SE3:QUAT 931 981 -0.24441 -3.02352 -0.181153 0.0286611 -0.000216941 0.00731696 0.999562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 -0.00181976 -0.234176 399.754 -8.59454 100.241 +EDGE_SE3:QUAT 932 982 0.033071 -3.04145 0.0382333 0.0328654 -0.000276999 -0.0216878 0.999224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.568 0.00376521 0.28914 399.676 -9.85626 100.277 +EDGE_SE3:QUAT 933 983 0.0436633 -3.1605 -0.195206 0.0311232 -0.00213829 0.0383977 0.998775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 -0.0132608 -1.78336 399.706 -9.31801 100.151 +EDGE_SE3:QUAT 934 984 -0.0459296 -2.85428 -0.186596 0.0335768 -0.000885473 0.00153953 0.999435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.55 -0.00331102 -0.473292 399.661 -10.0671 100.339 +EDGE_SE3:QUAT 935 985 0.0203099 -2.95208 -0.0260574 0.0342324 0.0015652 0.0241032 0.999122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.531 -0.00028417 0.286584 399.648 -10.2722 100.294 +EDGE_SE3:QUAT 936 986 -0.182141 -3.10238 -0.238111 0.0349099 0.00146576 0.0100207 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.514 0.00268438 0.522207 399.634 -10.4697 100.357 +EDGE_SE3:QUAT 937 987 0.0267933 -3.04949 -0.129168 0.0293138 -0.00604185 0.00101859 0.999551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.0178128 -3.03689 399.728 -8.78831 100.283 +EDGE_SE3:QUAT 938 988 -0.0819009 -3.0526 -0.118019 0.0355676 0.00754207 -0.0393047 0.998566 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 0.0309739 4.60112 399.593 -10.6048 100.279 +EDGE_SE3:QUAT 939 989 -0.0570242 -2.99449 0.0191212 0.0343825 0.00439356 -0.0108157 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.0171918 2.41745 399.637 -10.2988 100.359 +EDGE_SE3:QUAT 940 990 0.0616481 -3.06456 0.0486347 0.0342515 -0.00436041 0.00279562 0.9994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.557 -0.0154669 -2.23548 399.64 -10.2665 100.365 +EDGE_SE3:QUAT 941 991 -0.0672321 -2.93812 -0.0297879 0.0353706 0.00757404 0.00368817 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 0.0262212 3.70516 399.602 -10.6087 100.413 +EDGE_SE3:QUAT 942 992 -0.0582761 -3.13893 -0.247103 0.0333622 -0.000483059 0.00376873 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.555 -0.0024439 -0.316697 399.666 -10.0028 100.333 +EDGE_SE3:QUAT 943 993 -0.0755444 -2.81495 -0.187806 0.0272364 -0.00140754 0.023291 0.999357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.00709753 -1.08343 399.776 -8.16198 100.171 +EDGE_SE3:QUAT 944 994 0.153973 -3.269 -0.0465982 0.033482 0.00439534 0.0280254 0.999037 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.564 0.00897005 1.63128 399.657 -10.0647 100.267 +EDGE_SE3:QUAT 945 995 -0.05785 -3 -0.11265 0.0349066 -0.00308053 -7.50981e-05 0.999386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.525 -0.0107137 -1.53706 399.631 -10.4654 100.372 +EDGE_SE3:QUAT 946 996 -0.101075 -3.34018 -0.00949362 0.0349673 -0.00816916 -0.0267769 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 -0.0244377 -3.5165 399.609 -10.5274 100.333 +EDGE_SE3:QUAT 947 997 0.116916 -3.00919 -0.132406 0.0267115 -0.00470592 0.0350763 0.999017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.0154989 -2.91106 399.775 -7.97855 100.112 +EDGE_SE3:QUAT 948 998 -0.0515803 -2.84711 -0.0145609 0.0272941 0.00378298 0.0112066 0.999557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 0.00888369 1.7066 399.771 -8.19357 100.22 +EDGE_SE3:QUAT 949 999 0.0227854 -3.11563 -0.0776197 0.0301067 -0.00085333 -0.00427382 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.00179393 -0.349132 399.728 -9.02866 100.27 +EDGE_SE3:QUAT 950 1000 -0.0304937 -3.03547 -0.11559 0.0348688 0.0068405 0.0194025 0.99918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.559 0.0203988 3.00995 399.618 -10.4805 100.355 +EDGE_SE3:QUAT 951 1001 0.0840092 -2.95577 -0.017715 0.0432742 0.000490774 -0.00275321 0.999059 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.251 0.00314416 0.316413 399.438 -12.9698 100.561 +EDGE_SE3:QUAT 952 1002 0.083814 -3.03054 -0.0857193 0.0299689 -0.00120682 -0.00211636 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.642 -0.0032353 -0.564878 399.73 -8.98711 100.27 +EDGE_SE3:QUAT 953 1003 -0.0817822 -3.00663 -0.136828 0.03951 0.00177503 0.0164026 0.999083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.376 0.00190627 0.497452 399.531 -11.8501 100.443 +EDGE_SE3:QUAT 954 1004 -0.133527 -3.11044 -0.21021 0.0427214 -0.0118818 0.0567721 0.997402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 -0.0502323 -7.37342 399.384 -12.67 100.362 +EDGE_SE3:QUAT 955 1005 0.163475 -3.11015 -0.0109611 0.0342356 -0.00783302 0.0248396 0.999074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 -0.0292259 -4.4215 399.621 -10.2249 100.341 +EDGE_SE3:QUAT 956 1006 0.088096 -3.15635 -0.127318 0.0351191 0.00754591 -0.0202135 0.99915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.601 0.0289743 4.19422 399.605 -10.4977 100.376 +EDGE_SE3:QUAT 957 1007 -0.0151472 -2.95095 -0.151123 0.0214482 -0.00768098 -0.0193536 0.999553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.881 -0.0165228 -3.5892 399.84 -6.46226 100.138 +EDGE_SE3:QUAT 958 1008 -0.0279193 -3.03789 -0.0273645 0.0311196 -0.00106493 0.00275806 0.999511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 -0.00383505 -0.583481 399.709 -9.33076 100.291 +EDGE_SE3:QUAT 959 1009 -0.275265 -2.85042 -0.0567159 0.0277317 0.00341552 -0.00314279 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.709 0.0098753 1.75892 399.765 -8.31391 100.238 +EDGE_SE3:QUAT 960 1010 0.0303055 -3.00106 -0.0687602 0.0360608 0.00603815 -0.0161681 0.999201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.54 0.0246629 3.36506 399.594 -10.791 100.394 +EDGE_SE3:QUAT 961 1011 0.207652 -3.07523 -0.10412 0.034656 -0.00533121 -0.0380196 0.998662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 -0.0103215 -1.86942 399.63 -10.4332 100.229 +EDGE_SE3:QUAT 962 1012 -0.0622008 -3.17816 -0.349235 0.0262435 -0.00324138 0.00468457 0.999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 -0.00904758 -1.69347 399.789 -7.8671 100.212 +EDGE_SE3:QUAT 963 1013 -0.106456 -3.08668 -0.0620185 0.0409895 -0.000582833 -0.000586087 0.999159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.328 -0.00218455 -0.27657 399.496 -12.2866 100.504 +EDGE_SE3:QUAT 964 1014 -0.164922 -3.05599 -0.0657857 0.0289426 0.00319455 0.0103986 0.999522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.675 0.00764428 1.41543 399.745 -8.68577 100.247 +EDGE_SE3:QUAT 965 1015 -0.031883 -3.03663 -0.245354 0.0225405 -0.00999892 0.0374453 0.998994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.958 -0.0183905 -5.49953 399.804 -6.68514 100.093 +EDGE_SE3:QUAT 966 1016 -0.141263 -3.00011 -0.0275538 0.0286029 0.00509781 0.00523895 0.999564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 0.0139425 2.45728 399.744 -8.58222 100.26 +EDGE_SE3:QUAT 967 1017 -0.0167885 -2.90299 -0.0969139 0.0321819 0.00160063 0.0223186 0.999232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 0.000544305 0.368476 399.689 -9.65751 100.262 +EDGE_SE3:QUAT 968 1018 -0.0860026 -3.04599 -0.132652 0.0223853 0.00407138 -0.0247975 0.999434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.83 0.0106195 2.3668 399.842 -6.69402 100.103 +EDGE_SE3:QUAT 969 1019 -0.0851597 -2.90807 -0.0658584 0.0233897 -0.000512958 0.0169421 0.999583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.783 -0.00302442 -0.493985 399.836 -7.01358 100.136 +EDGE_SE3:QUAT 970 1020 -0.0396013 -3.08293 0.0506673 0.0333269 -0.000346764 0.0011097 0.999444 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.556 -0.00139916 -0.19539 399.667 -9.99243 100.333 +EDGE_SE3:QUAT 971 1021 0.250576 -3.15329 -0.01005 0.0412528 0.00516626 -0.00231669 0.999133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.356 0.0219349 2.63674 399.479 -12.3621 100.529 +EDGE_SE3:QUAT 972 1022 -0.117976 -3.1559 -0.198695 0.0246855 -0.000494177 0.0187541 0.999519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.758 -0.00346966 -0.524562 399.817 -7.40196 100.148 +EDGE_SE3:QUAT 973 1023 0.0333009 -3.00712 -0.133243 0.028055 0.00709999 0.0124656 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 0.0189674 3.3377 399.745 -8.43015 100.253 +EDGE_SE3:QUAT 974 1024 0.0674308 -3.17344 -0.247803 0.0337763 0.000547476 0.0237491 0.999147 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.544 -0.00356754 -0.207702 399.658 -10.1307 100.286 +EDGE_SE3:QUAT 975 1025 0.0496622 -3.02014 -0.0797395 0.0288342 0.00912072 0.0136466 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 0.0259078 4.32122 399.719 -8.67017 100.285 +EDGE_SE3:QUAT 976 1026 0.0947565 -3.11326 -0.0268186 0.0338674 0.00210027 -0.0133142 0.999335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 0.00998998 1.31935 399.654 -10.1489 100.331 +EDGE_SE3:QUAT 977 1027 0.00946112 -2.96368 -0.199493 0.0292592 -0.000877627 -0.0184164 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 0.000586523 -0.115161 399.743 -8.77773 100.223 +EDGE_SE3:QUAT 978 1028 -0.155117 -2.95919 -0.00336052 0.0267387 -0.00230695 -0.00740194 0.999612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.719 -0.00516046 -1.03397 399.784 -8.02215 100.212 +EDGE_SE3:QUAT 979 1029 0.0282176 -2.97821 -0.0547399 0.0366573 0.00631054 0.013187 0.999221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.504 0.0203444 2.86135 399.582 -11.0058 100.41 +EDGE_SE3:QUAT 980 1030 0.0162313 -2.96715 -0.219687 0.0232633 -0.00270655 0.0424849 0.998823 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.805 -0.00979276 -1.94309 399.833 -6.95591 99.9909 +EDGE_SE3:QUAT 981 1031 -0.0333699 -3.10039 -0.0891244 0.0239158 -0.00165379 -0.0343541 0.999122 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.771 -5.28382e-05 -0.332913 399.828 -7.18545 100.054 +EDGE_SE3:QUAT 982 1032 0.0971304 -3.18518 -0.0758457 0.0334613 0.0128207 -0.006171 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.775 0.042577 6.53148 399.597 -10.0128 100.45 +EDGE_SE3:QUAT 983 1033 -0.00646451 -3.02791 -0.0224793 0.0321654 -0.000367835 -0.0248929 0.999172 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 0.0039573 0.296507 399.689 -9.64745 100.249 +EDGE_SE3:QUAT 984 1034 -0.0419264 -3.08604 -0.0624456 0.0243353 0.00301918 0.0692641 0.997297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.762 -0.000726212 0.492735 399.82 -7.34619 99.7004 +EDGE_SE3:QUAT 985 1035 0.00219053 -3.01637 -0.369443 0.0265583 0.00846838 0.00368883 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.808 0.0224611 4.17368 399.76 -7.96955 100.259 +EDGE_SE3:QUAT 986 1036 -0.0333529 -3.02544 -0.0404052 0.0305619 -0.00205563 -0.0082635 0.999497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.63 -0.00477508 -0.875419 399.718 -9.16771 100.276 +EDGE_SE3:QUAT 987 1037 -0.109172 -3.07893 -0.350339 0.0388706 0.00432951 -0.00280584 0.999231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.422 0.0175386 2.22736 399.539 -11.6494 100.466 +EDGE_SE3:QUAT 988 1038 0.067169 -3.02183 -0.227826 0.0245583 0.00226966 0.00153415 0.999695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 0.0053969 1.11163 399.817 -7.36587 100.184 +EDGE_SE3:QUAT 989 1039 0.0719154 -3.09438 0.0893046 0.0323066 -0.00174252 -0.0164357 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.584 -0.00222747 -0.551779 399.686 -9.69304 100.287 +EDGE_SE3:QUAT 990 1040 -0.0840367 -3.13153 -0.168456 0.0285082 0.00135172 -0.0236659 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 0.00750691 1.07967 399.755 -8.54328 100.191 +EDGE_SE3:QUAT 991 1041 -0.0433143 -3.24167 0.0373899 0.0275687 -0.00470278 0.00498241 0.999596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.0135031 -2.43233 399.763 -8.26234 100.242 +EDGE_SE3:QUAT 992 1042 -0.032313 -3.10775 -0.0399503 0.0343972 0.00239356 0.0360589 0.998755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.527 -0.000254331 0.450521 399.643 -10.3325 100.227 +EDGE_SE3:QUAT 993 1043 -0.0450076 -3.17491 -0.232357 0.0363585 -0.000844756 0.0138256 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.474 -0.00666806 -0.723264 399.603 -10.8983 100.379 +EDGE_SE3:QUAT 994 1044 0.0924275 -3.24373 -0.0502466 0.0330427 -0.00253732 0.00627191 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 -0.00965088 -1.39171 399.67 -9.9041 100.329 +EDGE_SE3:QUAT 995 1045 0.0513226 -3.13533 0.11357 0.0313985 -0.00309593 0.00193258 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 -0.0100515 -1.58304 399.7 -9.41349 100.302 +EDGE_SE3:QUAT 996 1046 -0.12181 -3.10575 0.0530604 0.0259255 0.00643985 -0.00430536 0.999634 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.788 0.016946 3.28539 399.782 -7.76867 100.23 +EDGE_SE3:QUAT 997 1047 0.0468625 -2.92249 -0.190572 0.0417175 0.00193219 0.00565476 0.999112 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.307 0.00609499 0.8231 399.477 -12.5065 100.521 +EDGE_SE3:QUAT 998 1048 0.158801 -3.07445 -0.0622193 0.0237083 -0.00677626 0.00117889 0.999695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.835 -0.0161099 -3.40373 399.813 -7.10809 100.201 +EDGE_SE3:QUAT 999 1049 0.0872764 -3.03741 -0.0709993 0.0253572 0.00628267 -0.000382963 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.794 0.0159565 3.14578 399.791 -7.60348 100.221 +EDGE_SE3:QUAT 1000 1050 0.0364527 -3.06329 -0.230868 0.0207782 -0.00398333 -0.013768 0.999681 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.844 -0.0074173 -1.81901 399.865 -6.24308 100.12 +EDGE_SE3:QUAT 1001 1051 -0.017474 -3.08181 -0.291564 0.0255903 0.00324614 0.0370529 0.99898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 0.00376087 1.05158 399.8 -7.70033 100.064 +EDGE_SE3:QUAT 1002 1052 -0.243078 -2.88971 -0.220245 0.0263384 0.000210494 0.0193039 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 -0.00211995 -0.199806 399.792 -7.90009 100.171 +EDGE_SE3:QUAT 1003 1053 0.160787 -3.1623 0.00306187 0.0362589 -0.00376989 -0.0151517 0.99922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.486 -0.00992706 -1.5529 399.601 -10.8821 100.379 +EDGE_SE3:QUAT 1004 1054 0.0172477 -3.13248 -0.0673503 0.0357406 0.000334527 0.0253573 0.999039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 -0.00526347 -0.37645 399.617 -10.7182 100.319 +EDGE_SE3:QUAT 1005 1055 0.00300913 -3.08044 -0.188548 0.0318431 0.00272728 0.0368838 0.998808 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 0.00131828 0.656583 399.694 -9.57033 100.171 +EDGE_SE3:QUAT 1006 1056 -0.165673 -3.03641 -0.0542256 0.0353798 -0.00198511 0.00333911 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.505 -0.00781553 -1.0623 399.623 -10.6059 100.377 +EDGE_SE3:QUAT 1007 1057 -0.0855289 -3.04582 -0.110658 0.0207626 0.00137216 -0.0307339 0.999311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.834 0.00525875 1.06795 399.869 -6.21992 100.038 +EDGE_SE3:QUAT 1008 1058 -0.107003 -3.13213 -0.186061 0.0365238 0.00023368 0.0142214 0.999232 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 -0.00293794 -0.194813 399.6 -10.9509 100.38 +EDGE_SE3:QUAT 1009 1059 -0.0528766 -3.05043 -0.152313 0.0239889 0.00702631 -0.0022163 0.999685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.835 0.0169232 3.54384 399.807 -7.1906 100.207 +EDGE_SE3:QUAT 1010 1060 -0.124881 -2.98574 0.0201914 0.0299458 0.00409863 -0.0438639 0.99858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 0.017713 2.8319 399.722 -8.94588 100.096 +EDGE_SE3:QUAT 1011 1061 0.00912172 -3.15744 -0.0800272 0.0232735 -0.00536131 -0.0206532 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.812 -0.0111016 -2.39017 399.827 -7.00239 100.137 +EDGE_SE3:QUAT 1012 1062 0.267354 -2.92757 0.107772 0.0299869 -0.00303734 -0.0307711 0.999072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 -0.00378117 -0.962849 399.727 -9.01205 100.179 +EDGE_SE3:QUAT 1013 1063 -0.0857843 -3.20239 -0.0271958 0.0326294 0.00706144 0.0206279 0.99923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.623 0.0201082 3.12269 399.662 -9.81244 100.306 +EDGE_SE3:QUAT 1014 1064 0.00202644 -3.35284 -0.0148275 0.0228517 -0.00754969 -0.0122591 0.999635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.858 -0.0171422 -3.60513 399.821 -6.87148 100.179 +EDGE_SE3:QUAT 1015 1065 -0.0557483 -3.26206 -0.0966394 0.0276275 -0.00301831 -0.00108856 0.999613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.706 -0.00818021 -1.49012 399.767 -8.28556 100.235 +EDGE_SE3:QUAT 1016 1066 -0.0688921 -3.10151 -0.0695297 0.022575 -0.00417673 -0.0224738 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.812 -0.0076597 -1.78221 399.841 -6.78989 100.112 +EDGE_SE3:QUAT 1017 1067 -0.0400608 -2.96519 -0.0261511 0.028226 0.00709396 -0.00997777 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 0.0206402 3.7138 399.74 -8.44926 100.267 +EDGE_SE3:QUAT 1018 1068 -0.0140463 -3.22367 -0.135489 0.0263978 0.00343274 0.00710228 0.99962 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.00819564 1.60281 399.786 -7.92131 100.212 +EDGE_SE3:QUAT 1019 1069 -0.00889372 -3.11194 -0.00547035 0.0451667 0.00115386 0.00611578 0.99896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.185 0.00270552 0.410228 399.388 -13.5377 100.609 +EDGE_SE3:QUAT 1020 1070 0.119134 -3.10407 -0.0784602 0.0257257 0.00154133 0.0348685 0.99906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 -0.00063878 0.231486 399.801 -7.72747 100.078 +EDGE_SE3:QUAT 1021 1071 0.0445396 -2.89137 -0.0238769 0.0382191 0.00434088 0.0205301 0.999049 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.429 0.0109963 1.69632 399.555 -11.4756 100.406 +EDGE_SE3:QUAT 1022 1072 0.0405111 -3.13078 -0.132292 0.02109 0.00269254 -0.0362358 0.999117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.84 0.00808609 1.8025 399.863 -6.30725 100.01 +EDGE_SE3:QUAT 1023 1073 0.032551 -3.02805 -0.0452315 0.0289972 -0.00527071 -0.0168436 0.999424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 -0.0131141 -2.3399 399.738 -8.71316 100.24 +EDGE_SE3:QUAT 1024 1074 -0.197006 -3.07459 -0.118671 0.0336247 0.00132908 -0.00608487 0.999415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 0.00580805 0.786562 399.66 -10.0801 100.337 +EDGE_SE3:QUAT 1025 1075 0.0554664 -3.11073 0.109185 0.0311788 -0.000850144 0.0311214 0.999029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 -0.00848979 -1.00617 399.707 -9.34523 100.197 +EDGE_SE3:QUAT 1026 1076 -0.0760813 -3.03559 -0.119675 0.0342278 0.00397925 0.00582259 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.549 0.0123793 1.86802 399.643 -10.2667 100.358 +EDGE_SE3:QUAT 1027 1077 -0.166508 -3.09051 -0.0148712 0.0299105 -0.00531232 0.0252427 0.99922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 -0.0186879 -3.10577 399.719 -8.94241 100.23 +EDGE_SE3:QUAT 1028 1078 -0.0133315 -3.05111 -0.206278 0.0387829 0.00472758 -0.0279581 0.998845 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.448 0.0249526 3.00948 399.537 -11.6002 100.396 +EDGE_SE3:QUAT 1029 1079 -0.0219378 -3.04446 -0.102629 0.0318042 0.00388827 -0.000920442 0.999486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0125093 1.96003 399.69 -9.53535 100.314 +EDGE_SE3:QUAT 1030 1080 -0.0221662 -3.00588 0.0265332 0.0348778 0.00603904 -0.0176241 0.999218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 0.0239072 3.3846 399.619 -10.4351 100.364 +EDGE_SE3:QUAT 1031 1081 -0.143291 -3.18771 -0.242497 0.0279991 0.00124489 0.023035 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 -0.000119767 0.234901 399.764 -8.4029 100.183 +EDGE_SE3:QUAT 1032 1082 -0.0884373 -3.14039 -0.00446338 0.0283053 4.51818e-05 -0.0106857 0.999542 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 0.00183657 0.203993 399.76 -8.48824 100.229 +EDGE_SE3:QUAT 1033 1083 0.0597932 -2.98147 -0.125644 0.0258022 0.00588116 -0.00101999 0.999649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 0.0152464 2.95496 399.786 -7.73621 100.224 +EDGE_SE3:QUAT 1034 1084 0.0236397 -3.03106 -0.303444 0.031008 0.00283427 -0.0095394 0.99947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.0104374 1.59327 399.708 -9.29243 100.286 +EDGE_SE3:QUAT 1035 1085 0.063638 -3.10132 -0.0102661 0.0302604 0.000600271 -0.017606 0.999387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.00499179 0.619338 399.725 -9.07228 100.245 +EDGE_SE3:QUAT 1036 1086 -0.0182845 -3.16163 -0.0492317 0.0314076 0.00335549 -0.0147307 0.999392 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 0.0130337 1.95353 399.699 -9.40775 100.284 +EDGE_SE3:QUAT 1037 1087 -0.0705535 -2.90117 0.0136399 0.026434 -0.00377801 0.000384708 0.999643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.0100221 -1.89401 399.785 -7.92686 100.22 +EDGE_SE3:QUAT 1038 1088 0.0791077 -2.93616 -0.0308763 0.0369881 -0.00894671 -0.0182374 0.999109 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.536 -0.0302907 -4.06281 399.56 -11.1202 100.426 +EDGE_SE3:QUAT 1039 1089 -0.103707 -3.04427 -0.113873 0.0351527 -0.000493232 -0.0180992 0.999218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.506 0.00274017 0.135274 399.629 -10.5417 100.338 +EDGE_SE3:QUAT 1040 1090 -0.0173157 -3.0989 -0.157895 0.0283605 -0.00578251 -0.00290324 0.999577 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0160952 -2.84007 399.746 -8.50742 100.263 +EDGE_SE3:QUAT 1041 1091 -0.0740555 -3.10747 -0.126066 0.0263441 0.00549764 -0.0112994 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 0.0153605 2.92572 399.779 -7.88756 100.219 +EDGE_SE3:QUAT 1042 1092 0.104559 -3.06209 0.111713 0.0419294 -0.00172611 0.0122108 0.999044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.304 -0.0113886 -1.1686 399.471 -12.5637 100.516 +EDGE_SE3:QUAT 1043 1093 -0.0955397 -3.19568 -0.0795252 0.0391477 0.00555592 0.0186614 0.999044 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.413 0.016736 2.33533 399.529 -11.756 100.442 +EDGE_SE3:QUAT 1044 1094 -0.0650137 -3.05473 -0.0704064 0.0316073 -0.00375159 -0.0247197 0.999188 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 -0.0072672 -1.40456 399.696 -9.49676 100.245 +EDGE_SE3:QUAT 1045 1095 0.129152 -3.19416 -0.265199 0.0331635 -0.00425813 0.00901499 0.9994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.588 -0.0157432 -2.3063 399.662 -9.93552 100.336 +EDGE_SE3:QUAT 1046 1096 -0.148981 -3.08871 -0.0483914 0.0426345 0.00883815 -0.0121896 0.998977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.391 0.0401664 4.72445 399.422 -12.7547 100.591 +EDGE_SE3:QUAT 1047 1097 0.00992533 -3.1456 -0.00346286 0.0255241 0.005336 0.026074 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.764 0.0112029 2.26579 399.794 -7.68303 100.143 +EDGE_SE3:QUAT 1048 1098 0.0585119 -3.11981 -0.170435 0.027107 -0.0018475 -0.005385 0.999616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.00423756 -0.835563 399.778 -8.1311 100.22 +EDGE_SE3:QUAT 1049 1099 -0.0788919 -3.01608 -0.082015 0.032604 0.00209454 0.0053481 0.999452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 0.00571363 0.941667 399.679 -9.7782 100.319 +EDGE_SE3:QUAT 1050 1100 0.0846936 -2.84773 -0.0178092 0.0354029 -0.00941212 -0.039519 0.998547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 -0.0277628 -3.85603 399.593 -10.6898 100.267 +EDGE_SE3:QUAT 1051 1101 0.0292993 -3.19096 -0.0247129 0.02582 0.00553388 -0.00607394 0.999633 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.776 0.0147414 2.8596 399.787 -7.73613 100.219 +EDGE_SE3:QUAT 1052 1102 0.0542849 -2.80355 -0.005091 0.0248312 -0.00407347 -0.0182986 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 -0.00826915 -1.76251 399.809 -7.46214 100.161 +EDGE_SE3:QUAT 1053 1103 0.0795033 -2.99578 -0.145515 0.0266005 -0.000617008 0.0110679 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.00318716 -0.484874 399.787 -7.9761 100.201 +EDGE_SE3:QUAT 1054 1104 0.0221612 -3.00317 -0.0829812 0.0240916 -0.00192336 0.000614212 0.999708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 -0.0046961 -0.970069 399.824 -7.22507 100.177 +EDGE_SE3:QUAT 1055 1105 0.0211163 -2.96602 -0.135401 0.0318195 0.00817256 -0.0152272 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.0270375 4.37355 399.668 -9.51471 100.332 +EDGE_SE3:QUAT 1056 1106 0.160901 -3.04948 -0.262677 0.0273372 0.00214628 0.0190771 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 0.00309215 0.759279 399.774 -8.20674 100.19 +EDGE_SE3:QUAT 1057 1107 -0.00241801 -2.91995 0.0207867 0.0338742 0.00137243 -0.0078718 0.999394 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.545 0.00640508 0.845403 399.655 -10.1543 100.34 +EDGE_SE3:QUAT 1058 1108 0.0591185 -2.98281 -0.0250635 0.0348386 0.00129217 -0.0439156 0.998427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.528 0.014455 1.56135 399.634 -10.437 100.177 +EDGE_SE3:QUAT 1059 1109 0.0638423 -3.14503 0.0594812 0.0312245 0.00195525 -0.00447545 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.616 0.00693083 1.06059 399.706 -9.36097 100.294 +EDGE_SE3:QUAT 1060 1110 0.0901483 -3.19161 -0.217534 0.0245791 0.00051777 -0.0100715 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 0.00247636 0.407215 399.819 -7.37056 100.171 +EDGE_SE3:QUAT 1061 1111 0.0732734 -2.94313 -0.196864 0.0314399 0.00695541 -0.0253139 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.688 0.0240911 3.95084 399.682 -9.39167 100.273 +EDGE_SE3:QUAT 1062 1112 -0.043966 -3.08859 0.0557771 0.036803 -0.000294723 0.00351113 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.458 -0.00203103 -0.224677 399.594 -11.0332 100.405 +EDGE_SE3:QUAT 1063 1113 -0.0642777 -3.2544 -0.212404 0.0287694 0.0047066 0.0370752 0.998887 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 0.00820685 1.70916 399.744 -8.66389 100.121 +EDGE_SE3:QUAT 1064 1114 0.032159 -3.17742 -0.0284652 0.034769 -0.00194514 -0.0205771 0.999182 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.517 -0.00182238 -0.54211 399.636 -10.4331 100.322 +EDGE_SE3:QUAT 1065 1115 -0.02792 -3.15506 -0.165897 0.0283077 -0.00466738 0.024523 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0158351 -2.7474 399.749 -8.46623 100.2 +EDGE_SE3:QUAT 1066 1116 0.104795 -3.08425 -0.204007 0.0229232 0.0164758 -0.0260988 0.999261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.178 0.0271142 8.59706 399.73 -6.78519 100.291 +EDGE_SE3:QUAT 1067 1117 -0.158638 -3.09852 -0.0296164 0.032916 -0.00810001 -0.0249708 0.999113 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 -0.0235552 -3.55141 399.651 -9.90965 100.301 +EDGE_SE3:QUAT 1068 1118 -0.111918 -3.16048 -0.105541 0.029891 -0.00552105 0.00743299 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.687 -0.0173784 -2.89179 399.719 -8.95442 100.285 +EDGE_SE3:QUAT 1069 1119 0.0454455 -3.04932 -0.090615 0.0332789 0.000158849 -0.046773 0.998351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 0.0105968 1.01212 399.667 -9.98019 100.116 +EDGE_SE3:QUAT 1070 1120 0.0289694 -3.03173 -0.20876 0.0322003 0.00443161 0.0432069 0.998537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.00592101 1.37606 399.683 -9.69621 100.132 +EDGE_SE3:QUAT 1071 1121 -0.159112 -3.22867 -0.121974 0.0312666 -0.000355113 -0.00714388 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 0.00028784 -0.0434192 399.707 -9.37598 100.288 +EDGE_SE3:QUAT 1072 1122 -0.158343 -2.99913 -0.134118 0.0220072 -0.000752976 0.00671109 0.999735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.807 -0.00229532 -0.46491 399.854 -6.5996 100.141 +EDGE_SE3:QUAT 1073 1123 -0.0339182 -3.00933 -0.117717 0.0279654 0.00574868 0.0311179 0.999108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 0.0124712 2.34811 399.754 -8.423 100.155 +EDGE_SE3:QUAT 1074 1124 -0.115012 -3.16768 -0.07791 0.0308311 0.00487678 0.0127956 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 0.0130385 2.19946 399.706 -9.25721 100.283 +EDGE_SE3:QUAT 1075 1125 -0.0255793 -3.22819 -0.117767 0.0290209 0.000988505 0.00522934 0.999565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.664 0.00198979 0.402837 399.747 -8.70365 100.25 +EDGE_SE3:QUAT 1076 1126 -0.00893484 -2.96332 0.026229 0.0308165 0.0028751 0.00735184 0.999494 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.00754051 1.30039 399.712 -9.24472 100.285 +EDGE_SE3:QUAT 1077 1127 0.105186 -2.96758 -0.0759412 0.0319681 0.00473128 0.0104734 0.999423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0133219 2.16254 399.685 -9.59515 100.309 +EDGE_SE3:QUAT 1078 1128 -0.0191909 -2.93195 -0.296513 0.0307287 0.00425185 -0.000801715 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 0.0131748 2.13903 399.709 -9.21315 100.296 +EDGE_SE3:QUAT 1079 1129 -0.00207403 -3.10804 -0.284215 0.0368034 0.000720592 0.00422073 0.999313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 0.00150451 0.266691 399.593 -11.0342 100.405 +EDGE_SE3:QUAT 1080 1130 0.0287871 -3.02091 -0.0798066 0.0290315 0.00217625 0.00750106 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.00509462 0.956631 399.745 -8.70904 100.25 +EDGE_SE3:QUAT 1081 1131 -0.01036 -2.95319 -0.267749 0.0332178 0.00215415 0.0176204 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.00332461 0.724686 399.667 -9.96788 100.302 +EDGE_SE3:QUAT 1082 1132 0.0065057 -3.04553 0.0311802 0.039734 -0.00541942 0.00414177 0.999187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.41 -0.0225653 -2.80483 399.514 -11.9054 100.494 +EDGE_SE3:QUAT 1083 1133 -0.0435569 -3.0335 0.0190937 0.0297436 -0.00240089 0.00191908 0.999553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 -0.00744862 -1.23375 399.732 -8.91808 100.269 +EDGE_SE3:QUAT 1084 1134 -0.0712779 -3.1773 -0.0214954 0.0234048 -0.00293799 0.000404218 0.999722 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.00690899 -1.47399 399.832 -7.01913 100.17 +EDGE_SE3:QUAT 1085 1135 0.133739 -3.27775 -0.174547 0.0265141 -0.00238151 -0.0155017 0.999525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 -0.0042303 -0.94322 399.787 -7.95907 100.19 +EDGE_SE3:QUAT 1086 1136 0.16106 -3.26226 0.0412023 0.0275023 -0.00163376 -0.0316576 0.999119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.697 0.000278545 -0.293498 399.772 -8.25928 100.127 +EDGE_SE3:QUAT 1087 1137 0.265508 -3.09031 -0.147831 0.0344129 -0.00728056 -0.0174569 0.999229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 -0.0222707 -3.27556 399.625 -10.3426 100.357 +EDGE_SE3:QUAT 1088 1138 0.117624 -3.10572 -0.107534 0.024004 0.00938478 0.00671841 0.999645 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.878 0.0228224 4.59434 399.793 -7.21024 100.228 +EDGE_SE3:QUAT 1089 1139 0.0900041 -3.01079 0.0336033 0.0335564 -0.00353789 -0.025058 0.999116 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.557 -0.00650977 -1.26194 399.658 -10.0799 100.281 +EDGE_SE3:QUAT 1090 1140 -0.0123915 -2.98739 -0.0590395 0.0190168 -0.00347602 0.00563719 0.999797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.872 -0.00688543 -1.80179 399.887 -5.69993 100.114 +EDGE_SE3:QUAT 1091 1141 -0.000347532 -2.9763 -0.070558 0.0358023 -0.000383942 0.0238385 0.999074 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 -0.00740478 -0.703426 399.615 -10.7329 100.329 +EDGE_SE3:QUAT 1092 1142 0.0170841 -3.03 -0.00536934 0.0295738 -0.00199698 0.00895629 0.99952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.00737838 -1.15653 399.736 -8.86469 100.258 +EDGE_SE3:QUAT 1093 1143 0.0794835 -3.01918 -0.0688588 0.0290446 0.00622254 -0.0175008 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.725 0.0195801 3.41353 399.73 -8.68739 100.254 +EDGE_SE3:QUAT 1094 1144 0.108576 -3.19047 -0.156856 0.0247657 -0.00806007 0.00533262 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.843 -0.0199967 -4.10792 399.79 -7.41764 100.228 +EDGE_SE3:QUAT 1095 1145 -0.0581562 -2.90244 0.012481 0.0217164 0.00100312 -0.0144222 0.99966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.814 0.00348936 0.689134 399.858 -6.51068 100.122 +EDGE_SE3:QUAT 1096 1146 0.115824 -3.19631 -0.0213371 0.0210462 -0.00271612 -0.00482014 0.999763 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 -0.00534459 -1.29666 399.864 -6.315 100.135 +EDGE_SE3:QUAT 1097 1147 0.231058 -2.97191 -0.0633144 0.0276514 0.00635513 0.0123893 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 0.0164692 2.96979 399.755 -8.30746 100.24 +EDGE_SE3:QUAT 1098 1148 0.0906347 -3.0823 -0.0654172 0.0334868 -0.00358366 -0.0208923 0.999214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.00758745 -1.36979 399.659 -10.0559 100.299 +EDGE_SE3:QUAT 1099 1149 -0.0709827 -2.99242 -0.100519 0.0263069 0.00450799 -0.0334203 0.999085 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 0.0146809 2.77788 399.782 -7.86005 100.115 +EDGE_SE3:QUAT 1100 1150 -0.217694 -3.0471 -0.241971 0.0297868 -0.00104097 0.0154208 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.649 -0.00576453 -0.795465 399.733 -8.92917 100.244 +EDGE_SE3:QUAT 1101 1151 -0.133997 -3.18039 -0.298347 0.0292744 0.000143701 -0.0227225 0.999313 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 0.00428233 0.470694 399.743 -8.77865 100.206 +EDGE_SE3:QUAT 1102 1152 -0.120782 -3.10771 -0.132829 0.0270887 -0.00113342 -0.0145788 0.999526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 -0.000939379 -0.329351 399.779 -8.12721 100.199 +EDGE_SE3:QUAT 1103 1153 0.0651546 -3.08526 0.0333165 0.0268412 0.000114597 0.0247665 0.999333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.00324416 -0.34145 399.784 -8.05083 100.155 +EDGE_SE3:QUAT 1104 1154 -0.13073 -3.10417 -0.0207559 0.0285579 -0.00129457 0.0133211 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.00579308 -0.874895 399.754 -8.56063 100.229 +EDGE_SE3:QUAT 1105 1155 0.000154459 -3.19468 -0.219612 0.0357946 -0.00555514 -0.0157517 0.99922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.517 -0.0165022 -2.43579 399.604 -10.7488 100.378 +EDGE_SE3:QUAT 1106 1156 -0.0526983 -3.14509 -0.0514529 0.0272714 -0.00213684 0.00584157 0.999609 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.00663244 -1.16326 399.775 -8.17581 100.223 +EDGE_SE3:QUAT 1107 1157 0.021276 -3.03634 0.0578121 0.0345079 0.00294103 0.00928125 0.999357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 0.00802914 1.27676 399.64 -10.3516 100.354 +EDGE_SE3:QUAT 1108 1158 -0.034091 -3.05927 -0.0180954 0.0204186 0.00288 0.0205411 0.999576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.84 0.00437899 1.18735 399.872 -6.13649 100.087 +EDGE_SE3:QUAT 1109 1159 0.0976821 -2.96001 -0.091843 0.0333582 0.00392163 -0.0190069 0.999255 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.585 0.0165631 2.33866 399.659 -9.98705 100.312 +EDGE_SE3:QUAT 1110 1160 -0.0205294 -3.13789 0.114621 0.029621 -0.000853621 -0.0240002 0.999273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.649 0.00168696 8.7049e-05 399.737 -8.88735 100.206 +EDGE_SE3:QUAT 1111 1161 0.091867 -2.94575 -0.372363 0.021789 -0.00569113 0.0199663 0.999547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.861 -0.0129353 -3.10474 399.844 -6.51225 100.128 +EDGE_SE3:QUAT 1112 1162 0.162605 -3.15417 -0.179408 0.0237091 -0.00549323 -0.0102897 0.999651 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.81 -0.0123701 -2.59885 399.82 -7.12167 100.178 +EDGE_SE3:QUAT 1113 1163 0.0157016 -3.09259 0.0738619 0.0294374 0.00554588 0.0186886 0.999377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.683 0.0138899 2.44012 399.729 -8.84809 100.243 +EDGE_SE3:QUAT 1114 1164 0.0998559 -3.04731 -0.27322 0.0167544 0.00738572 -0.0262317 0.999488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.971 0.0109475 3.95418 399.893 -4.98666 100.058 +EDGE_SE3:QUAT 1115 1165 0.0358571 -3.03004 -0.157249 0.0222896 -0.00320336 0.0152026 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.00829708 -1.80399 399.846 -6.67553 100.135 +EDGE_SE3:QUAT 1116 1166 0.0257678 -3.09835 -0.0826716 0.0281277 -0.0025231 -0.00826974 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 -0.00585505 -1.12106 399.76 -8.43915 100.234 +EDGE_SE3:QUAT 1117 1167 -0.0353658 -3.05448 -0.151444 0.0256703 0.0074331 -0.017484 0.99949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.82 0.0194308 3.98348 399.779 -7.67177 100.21 +EDGE_SE3:QUAT 1118 1168 0.0758524 -2.9502 -0.244958 0.0203842 -0.0020988 -0.00589712 0.999773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.839 -0.00382626 -0.976873 399.874 -6.11645 100.124 +EDGE_SE3:QUAT 1119 1169 -0.00501287 -2.75295 -0.2332 0.0286603 0.00255627 -0.0197703 0.99939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 0.0102046 1.61665 399.75 -8.58481 100.214 +EDGE_SE3:QUAT 1120 1170 -0.128876 -3.07645 -0.0519347 0.0255143 0.000907675 0.00182752 0.999672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 0.00207746 0.425601 399.804 -7.65212 100.195 +EDGE_SE3:QUAT 1121 1171 0.175866 -3.02884 0.142398 0.0259403 0.00207455 -0.0245827 0.999359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 0.00834258 1.41858 399.796 -7.7699 100.146 +EDGE_SE3:QUAT 1122 1172 -0.0466014 -3.01999 -0.124203 0.0330126 0.00688047 -0.0376865 0.99872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.0263353 4.17953 399.65 -9.84717 100.229 +EDGE_SE3:QUAT 1123 1173 0.0476419 -2.8824 -0.029238 0.0275574 -0.0093678 0.0074387 0.999549 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.817 -0.025766 -4.80502 399.736 -8.24833 100.286 +EDGE_SE3:QUAT 1124 1174 0.113472 -3.02205 0.0360127 0.0310832 0.00205863 0.0302489 0.999057 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 0.000596749 0.463783 399.709 -9.33431 100.2 +EDGE_SE3:QUAT 1125 1175 0.164588 -2.921 -0.0232025 0.026715 -0.00582107 -0.00657821 0.999604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 -0.0149825 -2.80343 399.773 -8.0187 100.232 +EDGE_SE3:QUAT 1126 1176 -0.067375 -2.962 -0.0608439 0.0174906 -0.00128798 -0.0135316 0.999755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.879 -0.00144913 -0.501726 399.908 -5.25001 100.074 +EDGE_SE3:QUAT 1127 1177 0.111208 -3.27 -0.00309067 0.0354369 0.00158982 -0.015009 0.999258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.505 0.00926055 1.11284 399.622 -10.6199 100.357 +EDGE_SE3:QUAT 1128 1178 0.0696515 -2.92745 -0.232218 0.0300503 -0.00994744 0.0226102 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.0294067 -5.37722 399.687 -8.96429 100.297 +EDGE_SE3:QUAT 1129 1179 -0.0872156 -3.00687 -0.242848 0.0254769 -0.000555419 0.000748768 0.999675 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 -0.00150994 -0.288991 399.805 -7.64049 100.195 +EDGE_SE3:QUAT 1130 1180 0.135662 -2.98974 -0.166074 0.0338383 0.000550627 0.0373005 0.998731 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 -0.00663679 -0.48199 399.656 -10.1521 100.205 +EDGE_SE3:QUAT 1131 1181 0.0126317 -3.00361 0.0692822 0.0209038 -0.00826662 0.0249087 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.93 -0.0159939 -4.443 399.84 -6.22804 100.122 +EDGE_SE3:QUAT 1132 1182 0.087144 -3.00094 0.00257029 0.0207338 0.00271383 -0.00236082 0.999779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.838 0.00579402 1.38579 399.868 -6.21741 100.134 +EDGE_SE3:QUAT 1133 1183 0.0226019 -3.04873 -0.299544 0.0369747 0.00182385 0.00522969 0.999301 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.456 0.00532112 0.794822 399.589 -11.0867 100.409 +EDGE_SE3:QUAT 1134 1184 -0.140581 -3.05227 0.0454369 0.0340086 -0.00417558 -0.0305949 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.546 -0.00759402 -1.46002 399.647 -10.2236 100.261 +EDGE_SE3:QUAT 1135 1185 0.0316004 -2.98084 -0.193694 0.0274197 -0.00324149 0.00218293 0.999616 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 -0.00916366 -1.65561 399.77 -8.22119 100.233 +EDGE_SE3:QUAT 1136 1186 0.0678883 -3.03565 -0.13131 0.0239932 -0.00129441 0.0134598 0.999621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.774 -0.0045858 -0.840491 399.826 -7.19257 100.156 +EDGE_SE3:QUAT 1137 1187 -0.0966377 -3.0895 -0.144126 0.0333788 -0.00111089 -0.00621228 0.999423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.555 -0.00232495 -0.430502 399.665 -10.0095 100.331 +EDGE_SE3:QUAT 1138 1188 -0.191259 -3.12618 -0.287744 0.033108 0.00367681 -0.0289756 0.999025 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 0.0173416 2.41067 399.664 -9.90648 100.259 +EDGE_SE3:QUAT 1139 1189 0.120915 -2.91691 -0.0350008 0.0319231 0.00439022 -0.000526399 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 0.0140856 2.20333 399.687 -9.57113 100.319 +EDGE_SE3:QUAT 1140 1190 0.11299 -3.07753 -0.0105921 0.0239788 0.0058641 0.0576908 0.998029 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.789 0.00933539 2.09287 399.816 -7.26306 99.8554 +EDGE_SE3:QUAT 1141 1191 0.0181987 -3.08558 0.044592 0.0400019 0.00285354 -0.00667895 0.999173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.373 0.0133997 1.58493 399.516 -11.9869 100.482 +EDGE_SE3:QUAT 1142 1192 0.0601452 -3.00042 0.150736 0.0262266 -0.00443699 -0.0151156 0.999532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 -0.00998197 -1.97897 399.786 -7.87867 100.195 +EDGE_SE3:QUAT 1143 1193 0.0722748 -3.04419 -0.145982 0.0239483 -0.00268554 -0.00153866 0.999708 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.78 -0.00626863 -1.32 399.825 -7.18312 100.177 +EDGE_SE3:QUAT 1144 1194 0.0237231 -3.05141 -0.215397 0.0248931 -0.00179793 0.0163518 0.999555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 -0.00634854 -1.14243 399.812 -7.45999 100.162 +EDGE_SE3:QUAT 1145 1195 0.028394 -3.23374 -0.246211 0.0301127 -0.00604162 0.0483206 0.99836 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0219021 -3.8851 399.709 -8.97343 100.076 +EDGE_SE3:QUAT 1146 1196 0.223023 -3.01226 0.118686 0.038198 -0.00344223 -0.00782757 0.999234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.428 -0.0109679 -1.5395 399.558 -11.4563 100.439 +EDGE_SE3:QUAT 1147 1197 0.0295023 -2.99339 -0.110198 0.0323057 -0.00800081 0.0129604 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0269022 -4.2483 399.66 -9.66448 100.345 +EDGE_SE3:QUAT 1148 1198 -0.0636762 -3.05069 0.0395257 0.0315778 -0.00865198 -0.0468456 0.998365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.022074 -3.4273 399.675 -9.55209 100.118 +EDGE_SE3:QUAT 1149 1199 0.0128021 -3.04374 -0.148374 0.033564 0.000784813 -0.0453453 0.998407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.559 0.0123547 1.30354 399.66 -10.0597 100.136 +EDGE_SE3:QUAT 1150 1200 0.0837259 -3.23437 -0.161845 0.0238073 -0.00145551 -0.0108656 0.999656 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.775 -0.0022566 -0.572135 399.829 -7.14344 100.159 +EDGE_SE3:QUAT 1151 1201 -0.00140064 -3.01718 -0.0967987 0.0289722 -0.00456776 0.00105292 0.999569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.0133589 -2.30062 399.74 -8.68659 100.266 +EDGE_SE3:QUAT 1152 1202 0.0271031 -3.06013 0.00867464 0.0391203 0.00370033 -0.000459999 0.999228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.406 0.0145684 1.8585 399.535 -11.7264 100.469 +EDGE_SE3:QUAT 1153 1203 0.0217358 -2.96145 -0.106814 0.0300736 0.00771536 0.00112511 0.999517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.0231283 3.83502 399.705 -9.0184 100.312 +EDGE_SE3:QUAT 1154 1204 0.0270931 -2.91063 0.0451615 0.0383311 -0.00228716 -0.00718 0.999237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.417 -0.00668452 -0.97698 399.557 -11.4942 100.439 +EDGE_SE3:QUAT 1155 1205 0.0800109 -2.89701 -0.183108 0.0356678 -0.00443746 0.0365596 0.998685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.541 -0.0228456 -2.99571 399.608 -10.6625 100.27 +EDGE_SE3:QUAT 1156 1206 -0.0248295 -3.01964 -0.0582447 0.0231497 -0.00396901 -0.0152167 0.999608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.801 -0.00790169 -1.7719 399.833 -6.95517 100.147 +EDGE_SE3:QUAT 1157 1207 0.113841 -3.10738 -0.114207 0.0291575 0.00542194 -0.00710848 0.999535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 0.016602 2.83343 399.733 -8.7352 100.272 +EDGE_SE3:QUAT 1158 1208 0.038877 -2.98515 -0.256207 0.0356065 -0.0118843 0.0207942 0.999079 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.0417233 -6.38094 399.56 -10.6223 100.447 +EDGE_SE3:QUAT 1159 1209 0.0217916 -3.14152 0.148494 0.02244 -0.00145202 0.0269836 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.805 -0.00575493 -1.08838 399.848 -6.72319 100.081 +EDGE_SE3:QUAT 1160 1210 0.043156 -3.04312 -0.0215019 0.0373438 -0.00175524 -0.0165061 0.999165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.443 -0.00196922 -0.506669 399.581 -11.2016 100.392 +EDGE_SE3:QUAT 1161 1211 -0.160744 -2.9101 -0.152645 0.0269653 -0.00328117 -0.0317571 0.999126 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 -0.00452581 -1.12452 399.778 -8.10876 100.122 +EDGE_SE3:QUAT 1162 1212 -0.0771665 -2.93696 -0.078103 0.0302683 -0.00278066 -0.000203944 0.999538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.00836908 -1.38552 399.722 -9.07626 100.28 +EDGE_SE3:QUAT 1163 1213 0.0374038 -2.82418 -0.000826757 0.0306709 -0.00383932 0.00204714 0.99952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 -0.0120891 -1.95579 399.712 -9.19502 100.292 +EDGE_SE3:QUAT 1164 1214 -0.230059 -3.00784 7.51296e-05 0.0291339 0.00114181 -0.028229 0.999176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.00789986 1.06326 399.744 -8.73107 100.178 +EDGE_SE3:QUAT 1165 1215 0.033549 -2.82354 -0.0558731 0.033439 0.00264117 0.0126189 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.00609956 1.06601 399.662 -10.0329 100.323 +EDGE_SE3:QUAT 1166 1216 -0.00977411 -3.07625 -0.188491 0.0362883 0.00854708 -0.0207828 0.999089 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.0332315 4.72068 399.573 -10.8422 100.411 +EDGE_SE3:QUAT 1167 1217 0.0216891 -2.93679 -0.0716218 0.0393601 0.003361 -0.011935 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.401 0.016569 1.95976 399.53 -11.7907 100.46 +EDGE_SE3:QUAT 1168 1218 0.0706638 -3.06932 -0.137611 0.0306095 -0.00169681 -0.00566401 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.00414664 -0.74368 399.718 -9.18046 100.28 +EDGE_SE3:QUAT 1169 1219 0.156672 -3.09943 -0.0141817 0.0350558 0.00521648 -0.0161629 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.555 0.0212468 2.94494 399.619 -10.493 100.365 +EDGE_SE3:QUAT 1170 1220 0.00982461 -2.92941 -0.0510959 0.0286214 -0.00424306 0.00680399 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 -0.013005 -2.23685 399.747 -8.57676 100.255 +EDGE_SE3:QUAT 1171 1221 0.0582776 -3.09627 -0.169073 0.0339196 -0.0050759 -0.0506211 0.998129 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -0.00642811 -1.50051 399.647 -10.2256 100.099 +EDGE_SE3:QUAT 1172 1222 0.104497 -3.0923 -0.0486395 0.0293748 -0.00474635 0.0133287 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 -0.01559 -2.60606 399.731 -8.79566 100.259 +EDGE_SE3:QUAT 1173 1223 0.0400036 -3.0597 -0.00726114 0.0351251 0.00142939 -0.0231317 0.999114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.515 0.0104902 1.20081 399.628 -10.5252 100.32 +EDGE_SE3:QUAT 1174 1224 0.0599887 -3.19008 0.0384103 0.0300432 -0.00792139 -0.0028428 0.999513 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.0236102 -3.90704 399.704 -9.01202 100.313 +EDGE_SE3:QUAT 1175 1225 0.0836869 -2.95782 -0.264283 0.0195357 0.00236019 -0.00433063 0.999797 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.855 0.00489194 1.23045 399.883 -5.85747 100.117 +EDGE_SE3:QUAT 1176 1226 0.0365858 -2.99531 -0.0278675 0.0232512 -0.00200333 0.0170547 0.999582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.00631493 -1.23881 399.836 -6.96688 100.137 +EDGE_SE3:QUAT 1177 1227 -0.0305253 -3.07889 -0.18549 0.0354511 -0.00522484 -0.0175442 0.999204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.014728 -2.23588 399.613 -10.647 100.362 +EDGE_SE3:QUAT 1178 1228 -0.0319369 -3.01015 -0.177579 0.0331674 -0.000591969 0.0246629 0.999145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 -0.00728491 -0.786063 399.669 -9.94279 100.271 +EDGE_SE3:QUAT 1179 1229 -0.0523832 -2.98778 -0.239663 0.0312144 -0.00465585 -0.0417189 0.998631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 -0.00714275 -1.54161 399.701 -9.40113 100.127 +EDGE_SE3:QUAT 1180 1230 -0.0983646 -2.9026 0.12701 0.0327254 0.000283407 0.00786211 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 -0.000757677 -0.0127572 399.679 -9.81292 100.315 +EDGE_SE3:QUAT 1181 1231 -0.00253273 -3.13452 -0.205119 0.0268154 0.0062845 0.0330053 0.999076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 0.013759 2.60661 399.77 -8.08413 100.128 +EDGE_SE3:QUAT 1182 1232 -0.123887 -3.1491 0.0293308 0.0314587 0.00657575 6.96159e-05 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 0.020671 3.28413 399.686 -9.432 100.327 +EDGE_SE3:QUAT 1183 1233 0.0530003 -3.14802 -0.0660283 0.028909 0.00183514 0.0293276 0.99915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 0.00043578 0.407757 399.748 -8.68107 100.166 +EDGE_SE3:QUAT 1184 1234 -0.0920964 -3.03163 -0.0502112 0.0343049 -0.0108411 0.0154438 0.999233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 -0.0373042 -5.73417 399.598 -10.249 100.418 +EDGE_SE3:QUAT 1185 1235 0.150772 -3.17657 0.0119297 0.0292884 -0.00813577 -0.0159457 0.999411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 -0.0227641 -3.78439 399.718 -8.80779 100.274 +EDGE_SE3:QUAT 1186 1236 -0.0118933 -3.07448 -0.216914 0.0263025 0.0012026 -0.0121591 0.999579 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 0.00478801 0.792689 399.792 -7.88523 100.194 +EDGE_SE3:QUAT 1187 1237 0.107145 -3.11149 0.0407158 0.0360453 0.00568336 -0.00955429 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.529 0.0223128 3.04509 399.597 -10.7949 100.406 +EDGE_SE3:QUAT 1188 1238 0.0785587 -3.07704 -0.0334033 0.0301674 0.0128215 -0.027796 0.999076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.889 0.0345175 6.90887 399.657 -8.97188 100.324 +EDGE_SE3:QUAT 1189 1239 0.057874 -3.01272 -0.0126197 0.038073 -0.00630787 0.0321715 0.998737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.502 -0.0299422 -3.88217 399.546 -11.3733 100.37 +EDGE_SE3:QUAT 1190 1240 0.00429653 -3.0416 -0.15987 0.0309542 0.000645094 0.0266611 0.999165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 -0.00311234 -0.172826 399.712 -9.28635 100.217 +EDGE_SE3:QUAT 1191 1241 -0.153794 -3.16575 -0.134849 0.0278452 0.00672933 0.0223339 0.99934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.0167317 2.98814 399.751 -8.3803 100.21 +EDGE_SE3:QUAT 1192 1242 -0.0535129 -3.01837 -0.0370581 0.0238853 -0.000768417 0.0377344 0.999002 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.777 -0.00592948 -0.923954 399.828 -7.15938 100.031 +EDGE_SE3:QUAT 1193 1243 -0.0321359 -3.04146 -0.171921 0.0368564 -0.008314 -0.0207267 0.999071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.524 -0.0270615 -3.69283 399.567 -11.0831 100.406 +EDGE_SE3:QUAT 1194 1244 0.213947 -3.15164 -0.0665557 0.0267778 0.000838064 0.00617258 0.999622 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.0013608 0.3196 399.785 -8.03153 100.212 +EDGE_SE3:QUAT 1195 1245 -0.0477612 -2.98379 -0.224037 0.0221906 0.00168153 0.0137956 0.999657 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.805 0.00241409 0.656614 399.851 -6.66035 100.13 +EDGE_SE3:QUAT 1196 1246 -0.0851834 -3.07162 -0.135769 0.0342672 -0.00285623 -0.0213504 0.999181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.534 -0.00491295 -0.987293 399.645 -10.287 100.31 +EDGE_SE3:QUAT 1197 1247 -0.196691 -3.20303 -0.125991 0.0308721 0.00190502 -0.0035223 0.999515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 0.00651606 1.01692 399.713 -9.25579 100.287 +EDGE_SE3:QUAT 1198 1248 -0.150325 -2.90899 0.0488011 0.027796 0.000317842 0.0201015 0.999411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 -0.0022203 -0.176361 399.768 -8.33743 100.191 +EDGE_SE3:QUAT 1199 1249 0.0185902 -3.19486 -0.0656763 0.0385273 -0.00908986 -0.000392693 0.999216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.513 -0.0349674 -4.53108 399.522 -11.5479 100.503 +EDGE_SE3:QUAT 1200 1250 0.0357137 -3.20493 -0.0478291 0.0291234 -0.000744332 -0.0121345 0.999502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.000109029 -0.159864 399.745 -8.73534 100.24 +EDGE_SE3:QUAT 1201 1251 -0.200729 -2.95837 -0.0138394 0.0286809 -0.00280676 -0.0026069 0.999581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.00764505 -1.35752 399.75 -8.60203 100.251 +EDGE_SE3:QUAT 1202 1252 0.0326011 -3.11654 -0.0152223 0.0302147 0.00433889 -0.0187441 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 0.0156902 2.5069 399.718 -9.04399 100.255 +EDGE_SE3:QUAT 1203 1253 -0.0285094 -3.12084 -0.182164 0.0353313 -0.00695281 0.0131621 0.999265 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.0265246 -3.75164 399.605 -10.5733 100.395 +EDGE_SE3:QUAT 1204 1254 0.0110536 -3.01092 0.027117 0.0284208 -0.00818047 -0.0228283 0.999302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.0218508 -3.69685 399.733 -8.55969 100.231 +EDGE_SE3:QUAT 1205 1255 0.0674776 -3.06268 -0.0976775 0.0322324 0.00500793 0.00793198 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.0147918 2.34831 399.679 -9.67221 100.321 +EDGE_SE3:QUAT 1206 1256 -0.0196083 -2.9626 -0.153325 0.0364384 0.00121143 0.0114141 0.99927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.469 0.00138483 0.355495 399.601 -10.9272 100.386 +EDGE_SE3:QUAT 1207 1257 0.0859312 -3.26951 -0.0912336 0.0373818 0.000310425 -0.00533741 0.999287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.441 0.00264516 0.27467 399.581 -11.2064 100.417 +EDGE_SE3:QUAT 1208 1258 -0.0147072 -3.12703 -0.0531484 0.0266437 0.0115531 0.0358015 0.998937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.851 0.0328435 5.19594 399.738 -8.07249 100.165 +EDGE_SE3:QUAT 1209 1259 -0.014849 -3.08558 -0.149916 0.0361462 0.00262985 -0.0257357 0.999012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.497 0.0155908 1.87049 399.604 -10.8241 100.334 +EDGE_SE3:QUAT 1210 1260 0.0938793 -3.08888 -0.0800416 0.030352 0.00560929 0.00960599 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.015724 2.62744 399.712 -9.11169 100.287 +EDGE_SE3:QUAT 1211 1261 0.0756502 -3.09672 0.0478999 0.0302671 0.00843378 -0.0166908 0.999367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 0.0261932 4.51673 399.695 -9.04645 100.302 +EDGE_SE3:QUAT 1212 1262 -0.0436352 -3.17113 -0.0700736 0.0198803 0.002217 0.000869875 0.9998 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.848 0.00434359 1.09775 399.879 -5.96322 100.122 +EDGE_SE3:QUAT 1213 1263 -0.0794503 -3.06742 -0.191774 0.0228556 0.000367211 0.00306556 0.999734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 0.000518674 0.141486 399.843 -6.85512 100.156 +EDGE_SE3:QUAT 1214 1264 0.137458 -3.09804 -0.143777 0.0335613 -0.00349465 -0.045085 0.998413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 -0.00180395 -0.835434 399.658 -10.0976 100.139 +EDGE_SE3:QUAT 1215 1265 -0.12901 -3.00058 -0.155794 0.0279503 -0.00801375 -0.0114003 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.762 -0.021833 -3.81319 399.741 -8.39901 100.263 +EDGE_SE3:QUAT 1216 1266 0.19784 -2.96466 -0.0681702 0.0289366 -0.00764905 0.0218276 0.999314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 -0.02308 -4.19995 399.723 -8.64316 100.251 +EDGE_SE3:QUAT 1217 1267 0.009327 -3.11755 -0.187005 0.0319932 -0.00332046 -0.007669 0.999453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 -0.0091637 -1.5115 399.689 -9.59801 100.308 +EDGE_SE3:QUAT 1218 1268 -0.216884 -3.15929 -0.000483977 0.0351466 -0.00581562 -0.0179825 0.999203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 -0.0168104 -2.52489 399.617 -10.5583 100.358 +EDGE_SE3:QUAT 1219 1269 -0.0404176 -3.01787 -0.0454893 0.0317167 0.00460861 0.00619386 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.0135668 2.18445 399.69 -9.51554 100.312 +EDGE_SE3:QUAT 1220 1270 -0.0343912 -2.85548 0.0651266 0.0435368 -0.00353758 0.00010577 0.999046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.258 -0.0153881 -1.76861 399.426 -13.0482 100.577 +EDGE_SE3:QUAT 1221 1271 0.0500387 -3.16555 -0.0646421 0.0313185 -0.0100041 -0.0161373 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0307907 -4.6947 399.668 -9.42151 100.332 +EDGE_SE3:QUAT 1222 1272 -0.0950962 -3.27799 -0.034505 0.0243579 -0.00548528 -0.00268747 0.999685 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.8 -0.0131826 -2.70216 399.81 -7.30761 100.198 +EDGE_SE3:QUAT 1223 1273 0.000903979 -3.12157 -0.143615 0.0373093 0.00154958 0.0126838 0.999222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.444 0.00226022 0.489917 399.582 -11.1892 100.402 +EDGE_SE3:QUAT 1224 1274 0.103299 -2.88434 0.089176 0.0273509 -0.00511864 -0.0125484 0.999534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 -0.0126193 -2.35153 399.766 -8.21479 100.225 +EDGE_SE3:QUAT 1225 1275 -0.0430658 -3.02258 -0.326879 0.0231461 -0.00253741 -0.0166948 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 -0.00421234 -1.036 399.837 -6.95068 100.136 +EDGE_SE3:QUAT 1226 1276 0.131429 -3.06407 -0.116871 0.0286282 0.00339718 0.0458152 0.998534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.675 0.00250194 0.907921 399.751 -8.61904 100.04 +EDGE_SE3:QUAT 1227 1277 0.0874076 -3.00898 -0.201226 0.0257948 -0.00175971 0.0197868 0.99947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 -0.00697465 -1.18518 399.799 -7.72931 100.164 +EDGE_SE3:QUAT 1228 1278 0.0221527 -2.92567 -0.00606727 0.0305247 0.0122943 0.011206 0.999396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.808 0.0384264 5.93894 399.662 -9.17759 100.368 +EDGE_SE3:QUAT 1229 1279 -0.0827371 -3.1309 -0.126949 0.0335949 -0.00039411 -0.0114968 0.999369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.549 0.0012728 0.0348115 399.661 -10.0739 100.325 +EDGE_SE3:QUAT 1230 1280 -0.00340917 -3.02148 -0.128066 0.0292503 -0.0117477 -0.00171745 0.999502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.835 -0.0346094 -5.84193 399.688 -8.77236 100.352 +EDGE_SE3:QUAT 1231 1281 -0.0597199 -3.02169 0.0538403 0.0412793 -0.000708151 -0.0246672 0.998843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.319 0.00548124 0.257138 399.488 -12.378 100.451 +EDGE_SE3:QUAT 1232 1282 0.00633811 -3.18101 -0.128797 0.0339534 -0.00062793 0.0157351 0.999299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.541 -0.00571158 -0.63398 399.654 -10.1785 100.322 +EDGE_SE3:QUAT 1233 1283 0.123263 -2.99847 0.0159669 0.024663 -0.00638961 -0.0426798 0.998764 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.788 -0.0126403 -2.55692 399.804 -7.45298 100.022 +EDGE_SE3:QUAT 1234 1284 0.058116 -2.96013 -0.118725 0.0391528 0.00232957 0.0208481 0.999013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.388 0.00278037 0.673287 399.538 -11.7473 100.418 +EDGE_SE3:QUAT 1235 1285 -0.0321683 -3.14952 -0.17281 0.0294964 0.00245052 -0.000821092 0.999562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 0.00735102 1.23885 399.737 -8.84453 100.265 +EDGE_SE3:QUAT 1236 1286 -0.0432638 -2.92605 -0.126502 0.0298701 -0.00343679 -0.0555855 0.998001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.000564986 -0.717341 399.729 -8.99985 99.9623 +EDGE_SE3:QUAT 1237 1287 -0.164066 -3.11587 -0.138526 0.0228819 0.0056229 0.0191941 0.999538 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.823 0.0117643 2.54595 399.831 -6.88431 100.14 +EDGE_SE3:QUAT 1238 1288 0.0922468 -3.03399 0.0613566 0.0256538 0.000887883 0.0127737 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 0.000600139 0.247051 399.802 -7.69608 100.181 +EDGE_SE3:QUAT 1239 1289 -0.0299831 -3.07901 -0.380572 0.0318619 0.000771692 0.0122415 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 -2.81407e-05 0.15151 399.695 -9.55584 100.29 +EDGE_SE3:QUAT 1240 1290 0.0548115 -3.01175 -0.0288549 0.0373312 -0.0123718 0.00812175 0.999193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 -0.046252 -6.36333 399.519 -11.1671 100.523 +EDGE_SE3:QUAT 1241 1291 0.0094919 -3.12566 -0.139396 0.0302986 0.00048524 0.0121103 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 -0.000754995 0.0223114 399.725 -9.08681 100.261 +EDGE_SE3:QUAT 1242 1292 -0.0838546 -3.10407 -0.0704546 0.0327129 -0.00859308 -0.0013395 0.999427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 -0.0280169 -4.26719 399.65 -9.80914 100.372 +EDGE_SE3:QUAT 1243 1293 0.286475 -3.11071 -0.151375 0.033106 -0.00526836 -0.0141125 0.999338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0148962 -2.35106 399.661 -9.941 100.326 +EDGE_SE3:QUAT 1244 1294 -0.0813753 -3.09128 -0.0170196 0.0396417 -0.000605752 0.00644868 0.999193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.373 -0.00440991 -0.455737 399.528 -11.8824 100.468 +EDGE_SE3:QUAT 1245 1295 0.0220437 -3.08965 -0.243809 0.0266562 0.00334491 -0.00368328 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.731 0.00935201 1.73034 399.782 -7.99134 100.22 +EDGE_SE3:QUAT 1246 1296 0.1711 -3.22702 -0.229123 0.0279332 -0.000775851 0.0074459 0.999582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.689 -0.00331189 -0.512394 399.766 -8.37559 100.229 +EDGE_SE3:QUAT 1247 1297 -0.109196 -3.17172 -0.339867 0.0302187 0.00789998 -0.001269 0.999511 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 0.0239742 3.97062 399.701 -9.05803 100.318 +EDGE_SE3:QUAT 1248 1298 0.102301 -2.80005 -0.0583969 0.0390399 -0.00441643 -0.0148013 0.999118 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.407 -0.0130665 -1.85832 399.536 -11.7161 100.446 +EDGE_SE3:QUAT 1249 1299 -0.113522 -2.91989 -0.256649 0.026862 0.00644715 0.0121627 0.999544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.758 0.0163708 3.02544 399.768 -8.07081 100.228 +EDGE_SE3:QUAT 1250 1300 -0.0575381 -3.15703 -0.0173465 0.027843 -0.00964016 -0.0206251 0.999353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 -0.0266823 -4.47158 399.732 -8.38829 100.249 +EDGE_SE3:QUAT 1251 1301 -0.0208661 -3.04281 -0.262711 0.024248 -0.00609331 -0.0112463 0.999624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.807 -0.0141313 -2.88143 399.809 -7.28551 100.188 +EDGE_SE3:QUAT 1252 1302 -0.17397 -3.06393 -0.108863 0.0238839 -0.00273992 -0.0196454 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.777 -0.00447005 -1.08736 399.826 -7.17428 100.136 +EDGE_SE3:QUAT 1253 1303 -0.0151913 -3.10748 -0.0844892 0.0301462 0.0010968 0.00645101 0.999524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.637 0.00213748 0.431287 399.727 -9.04121 100.269 +EDGE_SE3:QUAT 1254 1304 0.0651676 -3.18321 -0.103595 0.0278158 -0.00211328 -0.000602331 0.999611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 -0.00578169 -1.04587 399.766 -8.34166 100.235 +EDGE_SE3:QUAT 1255 1305 -0.0440867 -3.07231 -0.112743 0.0286786 -0.00231216 -0.0178384 0.999427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.674 -0.00378436 -0.848064 399.751 -8.60867 100.217 +EDGE_SE3:QUAT 1256 1306 -0.123172 -3.18236 -0.125023 0.0248379 0.00639244 2.26566e-05 0.999671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.0158814 3.19456 399.799 -7.44835 100.214 +EDGE_SE3:QUAT 1257 1307 0.0905932 -3.08052 0.127835 0.0391144 -0.00361897 -0.0118304 0.999158 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.399 -0.0107036 -1.52931 399.536 -11.7339 100.452 +EDGE_SE3:QUAT 1258 1308 -0.100321 -3.02651 -0.221678 0.039901 -0.0047449 -0.0013103 0.999192 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.391 -0.0185227 -2.33787 399.513 -11.9614 100.493 +EDGE_SE3:QUAT 1259 1309 -0.0283104 -3.10143 -0.272325 0.0268907 -0.00042113 -0.0100979 0.999587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 0.000328874 -0.0475296 399.783 -8.06527 100.207 +EDGE_SE3:QUAT 1260 1310 -0.0214668 -3.03514 -0.187348 0.0316114 0.00158382 -0.0162983 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 0.00811788 1.10003 399.699 -9.47382 100.276 +EDGE_SE3:QUAT 1261 1311 0.0726882 -2.98127 -0.144517 0.0323949 -0.00927319 0.016582 0.999295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.0306714 -4.95506 399.649 -9.68073 100.354 +EDGE_SE3:QUAT 1262 1312 0.00471941 -3.09863 -0.116504 0.0332839 0.00162966 -0.0110126 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 0.0077699 1.03378 399.666 -9.97614 100.323 +EDGE_SE3:QUAT 1263 1313 0.1264 -3.18058 0.071293 0.0246612 -0.00115703 -0.0104403 0.999641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.758 -0.00159458 -0.423695 399.817 -7.39865 100.172 +EDGE_SE3:QUAT 1264 1314 -0.14519 -3.21131 -0.198725 0.0306889 0.000212482 0.00470373 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.623 -0.000234721 0.0195652 399.717 -9.20256 100.28 +EDGE_SE3:QUAT 1265 1315 0.0172603 -3.10497 -0.0672765 0.0307246 0.00247532 0.0051189 0.999512 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.00667506 1.14226 399.714 -9.21548 100.284 +EDGE_SE3:QUAT 1266 1316 -0.042448 -3.00457 -0.150366 0.0262155 -0.0165452 0.0169525 0.999376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.107 -0.0372788 -8.54091 399.682 -7.80073 100.378 +EDGE_SE3:QUAT 1267 1317 -0.0418052 -2.99817 -0.208835 0.016799 0.00447767 0.0178522 0.999689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.908 0.00706609 2.05783 399.908 -5.05504 100.065 +EDGE_SE3:QUAT 1268 1318 -0.0760421 -2.87396 -0.0420749 0.0236067 0.00195032 0.0236787 0.999439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 0.00203498 0.63892 399.832 -7.08991 100.113 +EDGE_SE3:QUAT 1269 1319 0.101262 -2.84592 -0.213601 0.0308853 0.00212787 -0.0275922 0.99914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.632 0.0113583 1.57339 399.711 -9.25038 100.216 +EDGE_SE3:QUAT 1270 1320 0.0903656 -3.00274 -0.141047 0.03809 -0.00219837 -0.00282895 0.999268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.425 -0.00755224 -1.03313 399.563 -11.4198 100.438 +EDGE_SE3:QUAT 1271 1321 0.0231358 -2.84813 -0.0955439 0.036785 0.00828333 0.0170676 0.999143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.53 0.027595 3.75969 399.569 -11.0552 100.419 +EDGE_SE3:QUAT 1272 1322 0.196866 -3.05021 0.025311 0.0327318 -0.00308407 0.00791858 0.999428 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 -0.0116119 -1.69599 399.674 -9.80921 100.323 +EDGE_SE3:QUAT 1273 1323 -0.0727416 -3.1449 0.0670576 0.0297005 -0.0057375 -0.0138961 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 -0.0152721 -2.61865 399.723 -8.92182 100.266 +EDGE_SE3:QUAT 1274 1324 -0.0156132 -3.00505 -0.295934 0.0279835 -0.00280497 -0.00687497 0.999581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.00684548 -1.28606 399.762 -8.39555 100.235 +EDGE_SE3:QUAT 1275 1325 0.0789107 -3.12503 0.142463 0.0309422 -0.000929341 0.0156534 0.999398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 -0.00580625 -0.75467 399.712 -9.27564 100.264 +EDGE_SE3:QUAT 1276 1326 -0.0672725 -3.153 -0.0609681 0.0408701 0.000378324 0.0321895 0.998646 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.334 -0.00914257 -0.599943 399.498 -12.2553 100.398 +EDGE_SE3:QUAT 1277 1327 0.0913388 -2.99895 0.0160893 0.0420721 -0.0021733 -0.0157037 0.998989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.294 -0.00361467 -0.688531 399.467 -12.6177 100.508 +EDGE_SE3:QUAT 1278 1328 0.0164034 -3.07669 0.0493066 0.0371611 -0.00490872 -0.00794612 0.999266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.474 -0.0163106 -2.27423 399.577 -11.148 100.423 +EDGE_SE3:QUAT 1279 1329 -0.0222329 -3.02261 -0.065597 0.0296415 -0.00347126 0.00805644 0.999522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 -0.01149 -1.87749 399.731 -8.88272 100.267 +EDGE_SE3:QUAT 1280 1330 0.0725016 -2.98363 -0.136355 0.0371603 -0.00464424 -0.00909485 0.999257 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 -0.0150088 -2.1165 399.578 -11.1485 100.419 +EDGE_SE3:QUAT 1281 1331 -0.0213452 -3.10214 -0.143385 0.0318529 0.00483214 0.018352 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.012223 2.06265 399.687 -9.56889 100.284 +EDGE_SE3:QUAT 1282 1332 0.0328465 -3.1208 -0.169905 0.0359 -0.00406541 0.0386791 0.998598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.53 -0.0223713 -2.86041 399.604 -10.7334 100.257 +EDGE_SE3:QUAT 1283 1333 -0.0300653 -2.87785 -0.011728 0.0301931 -0.00265745 -0.0122701 0.999465 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 -0.00588516 -1.10526 399.724 -9.06042 100.262 +EDGE_SE3:QUAT 1284 1334 -0.0541019 -3.16241 -0.0731676 0.0325672 -0.0006168 0.0241387 0.999178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 -0.00702803 -0.779374 399.681 -9.76288 100.261 +EDGE_SE3:QUAT 1285 1335 -0.123151 -3.11357 -0.0709806 0.0309308 -0.0110748 -0.00259137 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 -0.0344121 -5.48682 399.664 -9.27773 100.371 +EDGE_SE3:QUAT 1286 1336 0.0846766 -3.13313 -0.172657 0.035621 0.00609126 -0.0120582 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.55 0.0238046 3.29989 399.603 -10.664 100.395 +EDGE_SE3:QUAT 1287 1337 0.129784 -3.08153 -0.191773 0.0259844 0.00503775 -0.036744 0.998974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 0.0156057 3.08725 399.785 -7.75667 100.092 +EDGE_SE3:QUAT 1288 1338 0.0912647 -3.04488 -0.0878891 0.0361994 -0.00105218 0.000610653 0.999344 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.477 -0.00395768 -0.538729 399.606 -10.8526 100.394 +EDGE_SE3:QUAT 1289 1339 0.0633721 -3.02641 -0.176723 0.0170335 0.00880618 0.000951409 0.999816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.984 0.0151123 4.3934 399.882 -5.11 100.141 +EDGE_SE3:QUAT 1290 1340 0.040094 -3.13084 0.0623061 0.0346733 0.00194732 0.00333321 0.999391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.523 0.00595539 0.903293 399.638 -10.397 100.362 +EDGE_SE3:QUAT 1291 1341 0.117051 -2.93544 -0.200153 0.0386273 -0.000478053 0.000538302 0.999253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.404 -0.00200137 -0.251175 399.552 -11.5795 100.448 +EDGE_SE3:QUAT 1292 1342 -0.0954122 -3.11456 -0.214924 0.0320195 0.00904602 -0.0236839 0.999166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.722 0.0297176 4.97322 399.657 -9.55667 100.317 +EDGE_SE3:QUAT 1293 1343 -0.107863 -3.0765 -0.138434 0.0365556 0.000575028 -0.0100201 0.999281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 0.00475555 0.506813 399.599 -10.9583 100.391 +EDGE_SE3:QUAT 1294 1344 -0.0506967 -3.11434 -0.212269 0.0261184 0.00616627 -0.00892926 0.9996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.782 0.0166646 3.22141 399.78 -7.82114 100.225 +EDGE_SE3:QUAT 1295 1345 0.100709 -3.21198 -0.24691 0.0308012 -0.00295786 -0.0113541 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.00707641 -1.26776 399.712 -9.24273 100.277 +EDGE_SE3:QUAT 1296 1346 -0.0193429 -3.02744 -0.193487 0.0297198 -0.00279582 0.0338114 0.998982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 -0.0133463 -1.99802 399.73 -8.89443 100.16 +EDGE_SE3:QUAT 1297 1347 0.0708384 -3.25031 -0.118709 0.0350756 0.00701943 0.0104731 0.999305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 0.0228455 3.28563 399.612 -10.5299 100.39 +EDGE_SE3:QUAT 1298 1348 0.00108843 -2.97985 -0.0529146 0.0271421 -0.00392027 0.012613 0.999544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 -0.0120715 -2.16406 399.772 -8.12959 100.218 +EDGE_SE3:QUAT 1299 1349 -0.0774533 -2.99245 -0.102199 0.0337532 0.0020089 -0.0429209 0.998506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.564 0.0155479 1.87025 399.655 -10.1057 100.166 +EDGE_SE3:QUAT 1300 1350 -0.135449 -3.18796 -0.130342 0.025714 -0.00473361 0.0311189 0.999174 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 -0.0145224 -2.84357 399.791 -7.6828 100.122 +EDGE_SE3:QUAT 1301 1351 0.0863229 -3.01904 -0.146394 0.0273265 0.00529192 0.0496799 0.998377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 0.00828829 1.82466 399.767 -8.25065 99.9896 +EDGE_SE3:QUAT 1302 1352 -0.0886227 -3.07618 0.0863092 0.0306753 -0.000383019 -0.00677644 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 0.000101732 -0.066659 399.718 -9.19885 100.278 +EDGE_SE3:QUAT 1303 1353 0.098698 -3.03124 -0.145067 0.0210766 -0.00348886 -0.0435598 0.998822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 -0.00394978 -1.19033 399.863 -6.35392 99.9489 +EDGE_SE3:QUAT 1304 1354 -0.192031 -3.13288 0.0865867 0.029262 0.00830998 0.0202256 0.999333 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 0.0229894 3.79598 399.717 -8.80776 100.259 +EDGE_SE3:QUAT 1305 1355 0.0730041 -3.23254 -0.0434189 0.0269905 -0.00146635 -0.000161081 0.999635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 -0.00392947 -0.730092 399.781 -8.09422 100.22 +EDGE_SE3:QUAT 1306 1356 0.0144543 -3.20331 0.040632 0.0313499 0.0126279 -0.017157 0.999281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.839 0.0377613 6.63357 399.639 -9.35347 100.385 +EDGE_SE3:QUAT 1307 1357 0.000991237 -3.19475 -0.233741 0.0276496 -0.00109822 -0.0274082 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 0.00115594 -0.0938948 399.77 -8.29878 100.155 +EDGE_SE3:QUAT 1308 1358 -0.171001 -2.93116 -0.0731253 0.02586 -0.00131102 0.016597 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 -0.00551039 -0.912404 399.798 -7.75136 100.175 +EDGE_SE3:QUAT 1309 1359 0.0849326 -2.85309 -0.173527 0.0336883 8.48242e-05 0.00696374 0.999408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.546 -0.00129428 -0.0983355 399.66 -10.101 100.336 +EDGE_SE3:QUAT 1310 1360 0.0788349 -3.01811 -0.166758 0.0262079 0.00795857 -0.0014666 0.999624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 0.0209126 4.00077 399.769 -7.85608 100.251 +EDGE_SE3:QUAT 1311 1361 -0.0457107 -2.97227 0.0170211 0.0322901 -0.000651383 -0.016816 0.999337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.583 0.00140643 0.000348618 399.687 -9.68464 100.285 +EDGE_SE3:QUAT 1312 1362 0.0391832 -3.04532 -0.17623 0.0363059 0.00303012 -0.0140157 0.999238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.491 0.0143459 1.81825 399.6 -10.8761 100.384 +EDGE_SE3:QUAT 1313 1363 -0.0514189 -3.02893 -0.315396 0.0237823 -0.00794808 0.0109084 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.863 -0.0188341 -4.12824 399.804 -7.11429 100.204 +EDGE_SE3:QUAT 1314 1364 -0.0323157 -3.05847 -0.0958673 0.0292174 0.00451591 0.00469229 0.999552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.683 0.0125408 2.17408 399.736 -8.76532 100.267 +EDGE_SE3:QUAT 1315 1365 0.125174 -3.0133 -0.0689619 0.0371017 -0.00260666 0.0186983 0.999133 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.466 -0.0144122 -1.7174 399.583 -11.1134 100.385 +EDGE_SE3:QUAT 1316 1366 0.234237 -2.96419 -0.0508271 0.0373983 0.00622863 0.0434669 0.998335 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.46 0.012596 2.13085 399.568 -11.2688 100.248 +EDGE_SE3:QUAT 1317 1367 0.122871 -3.10854 -0.114482 0.0317386 0.0051183 0.00565375 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.0153337 2.44932 399.688 -9.52206 100.316 +EDGE_SE3:QUAT 1318 1368 0.0196499 -2.99553 -0.0891939 0.0330396 -0.00422743 0.0245678 0.999143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.0181555 -2.59753 399.664 -9.88604 100.284 +EDGE_SE3:QUAT 1319 1369 0.0294847 -3.09914 0.0669154 0.0248847 0.00137617 -0.0144236 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 0.00512516 0.902882 399.813 -7.45932 100.167 +EDGE_SE3:QUAT 1320 1370 -0.0243636 -3.11324 0.000406849 0.034483 -0.00211644 -0.0428606 0.998484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.523 0.00290052 -0.169453 399.642 -10.36 100.174 +EDGE_SE3:QUAT 1321 1371 -0.0885003 -3.08063 0.00394994 0.0297005 0.000385995 -0.0125512 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.648 0.00334357 0.416406 399.735 -8.90547 100.249 +EDGE_SE3:QUAT 1322 1372 -0.0644299 -3.1561 -0.1362 0.0388188 0.0059398 0.0310069 0.998747 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.42 0.0148355 2.24179 399.536 -11.675 100.373 +EDGE_SE3:QUAT 1323 1373 -0.129697 -2.82568 -0.0770265 0.0430461 -0.00438765 -0.0296086 0.998625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.267 -0.00832057 -1.42442 399.438 -12.9295 100.476 +EDGE_SE3:QUAT 1324 1374 -0.031255 -2.96979 -0.0713494 0.0246334 -0.00318192 0.00789957 0.99966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 -0.00862669 -1.70681 399.814 -7.3826 100.184 +EDGE_SE3:QUAT 1325 1375 -0.00792822 -3.10115 -0.0591035 0.030258 0.000555014 0.0147926 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.634 -0.00103142 0.00876816 399.725 -9.07521 100.253 +EDGE_SE3:QUAT 1326 1376 -0.0375512 -3.03737 -0.126621 0.038457 -6.85723e-05 0.0553721 0.997725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.418 -0.0160723 -1.30993 399.554 -11.5335 100.141 +EDGE_SE3:QUAT 1327 1377 0.123801 -3.1379 -0.177073 0.0293968 -0.00440519 -0.000769972 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 -0.0128304 -2.18745 399.733 -8.81549 100.273 +EDGE_SE3:QUAT 1328 1378 0.0473298 -3.06573 -0.112554 0.0341598 0.00170783 -0.00222067 0.999412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 0.00632619 0.898523 399.649 -10.2411 100.352 +EDGE_SE3:QUAT 1329 1379 -0.0299222 -2.98244 -0.0324959 0.0230538 -0.00219058 -0.0232837 0.999461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.79 -0.00267625 -0.772281 399.839 -6.9251 100.107 +EDGE_SE3:QUAT 1330 1380 0.0112869 -3.06834 0.0314856 0.0332077 0.00197266 -0.0256664 0.999117 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.571 0.0118063 1.49592 399.667 -9.94758 100.27 +EDGE_SE3:QUAT 1331 1381 0.221602 -3.09163 0.0614727 0.0309741 8.78808e-05 0.00612638 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.616 -0.000903138 -0.0699166 399.712 -9.28793 100.284 +EDGE_SE3:QUAT 1332 1382 0.118677 -3.11276 -0.261401 0.02547 -0.00254218 0.0147803 0.999563 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 -0.00815345 -1.49596 399.802 -7.63112 100.179 +EDGE_SE3:QUAT 1333 1383 -0.0791063 -3.12113 0.163113 0.0236095 0.00471228 0.00597033 0.999692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.804 0.0106789 2.27048 399.824 -7.08617 100.178 +EDGE_SE3:QUAT 1334 1384 0.0665855 -3.00528 0.0403633 0.0396403 -0.00382012 0.00693051 0.999183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.394 -0.0170706 -2.07216 399.522 -11.877 100.478 +EDGE_SE3:QUAT 1335 1385 0.00731679 -3.01045 -0.0693185 0.029337 0.00224929 0.0190011 0.999386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 0.00340847 0.789084 399.74 -8.80634 100.224 +EDGE_SE3:QUAT 1336 1386 0.0707095 -2.9723 -0.0640878 0.0351545 -0.00497847 -0.00510738 0.999356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 -0.0164207 -2.3789 399.62 -10.5444 100.384 +EDGE_SE3:QUAT 1337 1387 0.24516 -3.05638 -0.17008 0.0325813 0.000186239 -0.000625845 0.999469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 0.000738252 0.105261 399.682 -9.76916 100.318 +EDGE_SE3:QUAT 1338 1388 -0.133061 -3.07977 0.00842736 0.0388375 0.00142855 -0.0246077 0.998941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.406 0.0126801 1.28598 399.546 -11.6364 100.396 +EDGE_SE3:QUAT 1339 1389 0.0267053 -3.08914 -0.174307 0.0331816 0.00548942 -0.00210162 0.999432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 0.0185419 2.78411 399.658 -9.94594 100.351 +EDGE_SE3:QUAT 1340 1390 -0.065725 -3.16306 -0.22173 0.0331497 0.00370405 -0.0048122 0.999432 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 0.013186 1.94594 399.665 -9.93553 100.338 +EDGE_SE3:QUAT 1341 1391 0.249362 -2.97866 -0.137487 0.0327038 -0.000219217 -0.0326484 0.998932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 0.00621432 0.530786 399.679 -9.80903 100.215 +EDGE_SE3:QUAT 1342 1392 -0.0188619 -2.96372 0.0335782 0.0282573 -0.00647056 -0.0308339 0.999104 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.0150229 -2.70793 399.746 -8.51443 100.168 +EDGE_SE3:QUAT 1343 1393 0.101523 -3.01196 -0.0992638 0.0351212 0.000125646 0.055716 0.997829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.513 -0.0129034 -1.10984 399.629 -10.5366 100.062 +EDGE_SE3:QUAT 1344 1394 -0.10246 -3.06114 0.0283579 0.0312841 0.00696774 -0.0235911 0.999208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 0.0238579 3.92259 399.685 -9.34723 100.278 +EDGE_SE3:QUAT 1345 1395 0.126295 -3.02449 -0.119801 0.026744 0.00262805 -0.0149824 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 0.00890968 1.55331 399.782 -8.01255 100.198 +EDGE_SE3:QUAT 1346 1396 -0.164039 -2.81797 -0.128848 0.0347366 0.00417853 0.00669187 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 0.0130585 1.94759 399.631 -10.42 100.369 +EDGE_SE3:QUAT 1347 1397 0.0642075 -3.12925 -0.283189 0.0309068 0.00403866 0.00674229 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.011353 1.89261 399.707 -9.2728 100.292 +EDGE_SE3:QUAT 1348 1398 0.061399 -3.1661 -0.0734478 0.0324153 -0.00196758 0.0145731 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.0092651 -1.26602 399.683 -9.71393 100.298 +EDGE_SE3:QUAT 1349 1399 -0.14636 -3.15239 0.0734351 0.0369584 -0.00462731 0.0292169 0.998879 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.502 -0.0232823 -2.95688 399.579 -11.0535 100.346 +EDGE_SE3:QUAT 1350 1400 -0.140195 -3.13059 -0.116467 0.0271192 0.0101255 0.0030725 0.999576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.836 0.0276276 5.01111 399.739 -8.13695 100.29 +EDGE_SE3:QUAT 1351 1401 -0.0616465 -3.15171 -0.0461224 0.0234386 0.00174035 -0.0030475 0.999719 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 0.00439179 0.912599 399.834 -7.02854 100.166 +EDGE_SE3:QUAT 1352 1402 -0.122224 -2.78434 -0.193178 0.0348457 0.00177855 0.0119385 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 0.00332218 0.638702 399.635 -10.4518 100.351 +EDGE_SE3:QUAT 1353 1403 -0.0961264 -3.04238 -0.248621 0.0333458 -0.00201553 0.00569381 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.562 -0.00792222 -1.12062 399.665 -9.9958 100.334 +EDGE_SE3:QUAT 1354 1404 0.123914 -3.06153 -0.259859 0.03073 -0.00278803 -0.0153218 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.00580113 -1.11016 399.714 -9.22344 100.264 +EDGE_SE3:QUAT 1355 1405 -0.0435789 -3.06667 -0.0159335 0.0280576 0.00101248 0.00413294 0.999597 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 0.0021917 0.436316 399.763 -8.41481 100.235 +EDGE_SE3:QUAT 1356 1406 -0.0250662 -3.19135 -0.312431 0.036041 0.00158141 -0.0123314 0.999273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.487 0.00879237 1.05623 399.609 -10.8015 100.377 +EDGE_SE3:QUAT 1357 1407 -0.0337986 -3.29913 -0.120742 0.0276687 0.00749134 0.00545247 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 0.0204284 3.65316 399.748 -8.30453 100.265 +EDGE_SE3:QUAT 1358 1408 0.188488 -2.96307 -0.215817 0.0280847 -0.0031014 -0.00650978 0.99958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.00777079 -1.43991 399.76 -8.426 100.238 +EDGE_SE3:QUAT 1359 1409 0.0588821 -3.08888 -0.10601 0.0349777 0.00856944 0.013221 0.999264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.0282775 4.00281 399.605 -10.5081 100.396 +EDGE_SE3:QUAT 1360 1410 -0.130273 -3.03285 0.0446737 0.0332322 -0.00393829 -0.0304836 0.998975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 -0.00676067 -1.35814 399.664 -9.98953 100.245 +EDGE_SE3:QUAT 1361 1411 0.137714 -3.07736 -0.34693 0.0230592 0.00142993 0.0138561 0.999637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.789 0.00184936 0.522839 399.84 -6.92009 100.141 +EDGE_SE3:QUAT 1362 1412 0.0617815 -2.90856 -0.119507 0.0291841 0.00968608 -0.0129897 0.999443 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.794 0.0281601 5.06788 399.706 -8.72438 100.309 +EDGE_SE3:QUAT 1363 1413 0.000388562 -2.95835 -0.273994 0.0316468 -0.00219458 0.0094207 0.999452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 -0.00871132 -1.27506 399.697 -9.48515 100.296 +EDGE_SE3:QUAT 1364 1414 -0.117077 -2.94846 -0.154331 0.037122 -0.00746647 -0.0217431 0.999046 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.501 -0.023374 -3.24341 399.567 -11.161 100.398 +EDGE_SE3:QUAT 1365 1415 0.138866 -3.08177 -0.273103 0.0252237 -0.00716284 -0.0331674 0.999106 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.0161582 -3.07447 399.791 -7.61289 100.11 +EDGE_SE3:QUAT 1366 1416 0.0815604 -3.11526 -0.140667 0.0244491 -0.00280276 -0.010493 0.999642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 -0.00571118 -1.24662 399.818 -7.33844 100.173 +EDGE_SE3:QUAT 1367 1417 0.0851823 -3.00174 0.105478 0.0257641 -0.00603762 -0.008437 0.999614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.777 -0.0149437 -2.88674 399.787 -7.7363 100.216 +EDGE_SE3:QUAT 1368 1418 -0.0444368 -2.90327 -0.185914 0.0330893 0.00425205 0.00157411 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.585 0.0137535 2.09281 399.664 -9.92227 100.341 +EDGE_SE3:QUAT 1369 1419 -0.0490994 -3.12999 -0.0129322 0.0254471 -0.00355539 -0.00868448 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 -0.00808584 -1.64403 399.801 -7.63772 100.195 +EDGE_SE3:QUAT 1370 1420 -0.0343025 -3.09612 0.0298384 0.0273428 -0.00209955 -0.00355127 0.999618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.706 -0.00522751 -0.990823 399.774 -8.20121 100.226 +EDGE_SE3:QUAT 1371 1421 0.118178 -2.93711 -0.0889908 0.0391005 0.002456 -0.0288487 0.998816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.409 0.0176875 1.90179 399.537 -11.7082 100.384 +EDGE_SE3:QUAT 1372 1422 -0.0925934 -3.00313 -0.0839782 0.0324413 -0.0044912 -0.00613706 0.999445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 -0.0134589 -2.12411 399.677 -9.7324 100.325 +EDGE_SE3:QUAT 1373 1423 0.0799127 -3.13026 0.053292 0.0185464 0.00208069 -0.00687167 0.999802 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.869 0.00426867 1.11646 399.895 -5.56009 100.102 +EDGE_SE3:QUAT 1374 1424 -0.066994 -3.00604 -0.0426163 0.0404419 -0.000780312 0.00151136 0.99918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.347 -0.00363752 -0.426235 399.509 -12.1224 100.491 +EDGE_SE3:QUAT 1375 1425 0.313067 -2.91797 0.0345355 0.0361758 -0.00345242 0.00140676 0.999338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.0127995 -1.75477 399.603 -10.8443 100.401 +EDGE_SE3:QUAT 1376 1426 -0.160073 -3.05797 0.0140968 0.0352566 -0.00568491 -0.0163307 0.999229 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.534 -0.0166986 -2.49349 399.615 -10.5888 100.365 +EDGE_SE3:QUAT 1377 1427 0.0114447 -3.10837 -0.150238 0.0344469 -0.00336915 0.0139979 0.999303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.546 -0.0145228 -1.97178 399.639 -10.3184 100.346 +EDGE_SE3:QUAT 1378 1428 0.166134 -2.88169 -0.0126063 0.0282204 -0.000858664 0.0268692 0.99924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 -0.00655996 -0.883485 399.76 -8.4591 100.168 +EDGE_SE3:QUAT 1379 1429 0.0128448 -3.03928 -0.130835 0.0235373 0.00866994 0.0155832 0.999564 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.865 0.0206209 4.11275 399.805 -7.08532 100.191 +EDGE_SE3:QUAT 1380 1430 0.189056 -3.04874 0.102951 0.0281526 0.00576748 -0.0293237 0.999157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.0185383 3.37513 399.747 -8.40889 100.181 +EDGE_SE3:QUAT 1381 1431 0.00165198 -3.11531 -0.0230139 0.0335018 -0.00033054 -0.00528467 0.999425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 8.05758e-05 -0.0589121 399.663 -10.0453 100.334 +EDGE_SE3:QUAT 1382 1432 -0.208759 -2.98 -0.159831 0.0201559 0.00358896 -0.0238089 0.999507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.861 0.00844092 2.0809 399.872 -6.02877 100.076 +EDGE_SE3:QUAT 1383 1433 -0.0998267 -3.0062 -0.11769 0.0302615 -0.00320643 -0.0148391 0.999427 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.642 -0.00716611 -1.33227 399.722 -9.08397 100.258 +EDGE_SE3:QUAT 1384 1434 -0.0040618 -2.88701 -0.0346106 0.0275042 0.00489915 0.0101257 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 0.0123163 2.28078 399.764 -8.25775 100.232 +EDGE_SE3:QUAT 1385 1435 -0.232551 -2.85677 -0.0106074 0.0374492 0.00418994 -0.0231801 0.999021 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 0.0210599 2.61212 399.571 -11.2077 100.384 +EDGE_SE3:QUAT 1386 1436 0.0412898 -3.05322 -0.00766552 0.0446274 0.000575887 -0.0109061 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.205 0.00687571 0.579221 399.402 -13.3738 100.586 +EDGE_SE3:QUAT 1387 1437 0.0945153 -3.01835 -0.0651342 0.0376588 -0.0102009 0.00633692 0.999218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.576 -0.0390189 -5.23893 399.532 -11.2737 100.497 +EDGE_SE3:QUAT 1388 1438 0.00684625 -3.02375 -0.160322 0.0291947 0.00284599 -0.0104572 0.999515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.00988941 1.60494 399.741 -8.74865 100.252 +EDGE_SE3:QUAT 1389 1439 0.0533143 -2.92101 0.0682153 0.0335195 0.000170913 0.0172997 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 -0.00330741 -0.262415 399.663 -10.0513 100.307 +EDGE_SE3:QUAT 1390 1440 -0.0677061 -3.04323 0.0948217 0.0372161 0.000972057 0.0418426 0.99843 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.447 -0.00794409 -0.448698 399.584 -11.1685 100.241 +EDGE_SE3:QUAT 1391 1441 0.114623 -3.1265 -0.062847 0.0208402 -0.00502539 0.000635024 0.99977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.859 -0.0105002 -2.51987 399.86 -6.24968 100.148 +EDGE_SE3:QUAT 1392 1442 -0.0744187 -3.11913 -0.0777796 0.0425251 0.0065301 0.00626188 0.999054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.326 0.0258819 3.10034 399.441 -12.753 100.566 +EDGE_SE3:QUAT 1393 1443 0.0170717 -3.23287 0.0958371 0.028947 -0.00440098 -0.0202916 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.00983593 -1.8458 399.742 -8.6986 100.221 +EDGE_SE3:QUAT 1394 1444 -0.0186652 -3.12685 -0.268548 0.0250679 -0.00401096 -0.015322 0.99956 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.764 -0.0084748 -1.7736 399.806 -7.53034 100.175 +EDGE_SE3:QUAT 1395 1445 0.0617102 -3.20129 -0.315528 0.0344344 -0.0088836 0.0248019 0.99906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.0322154 -4.9486 399.61 -10.2788 100.359 +EDGE_SE3:QUAT 1396 1446 -0.0168841 -3.00355 -0.0743806 0.0385473 0.0146442 0.00349696 0.999143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.0570083 7.23658 399.469 -11.5598 100.592 +EDGE_SE3:QUAT 1397 1447 -0.0445362 -3.00702 -0.0515179 0.0271206 -0.00374939 -0.0211212 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 -0.00741757 -1.52918 399.774 -8.14943 100.184 +EDGE_SE3:QUAT 1398 1448 -0.0715959 -3.16938 -0.215106 0.0283719 -0.00601909 0.011277 0.999516 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.732 -0.0180688 -3.19942 399.743 -8.4939 100.256 +EDGE_SE3:QUAT 1399 1449 -0.117625 -3.25715 -0.0273246 0.0351648 0.00453777 -0.0242261 0.999078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.547 0.0206209 2.77635 399.619 -10.5212 100.332 +EDGE_SE3:QUAT 1400 1450 -0.11432 -3.22112 -0.143187 0.0296128 -0.00198957 -0.0160207 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 -0.00313423 -0.709228 399.736 -8.88664 100.239 +EDGE_SE3:QUAT 1401 1451 0.0970733 -3.03483 -0.170898 0.0291659 0.00798228 0.0164347 0.999408 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 0.0221308 3.70026 399.721 -8.77144 100.268 +EDGE_SE3:QUAT 1402 1452 0.0695612 -3.06127 -0.00410004 0.0398785 0.00737824 -0.0120438 0.999105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.448 0.0318786 3.97231 399.5 -11.9347 100.505 +EDGE_SE3:QUAT 1403 1453 -0.0691311 -3.16751 -0.135613 0.0278297 0.002466 -0.0483016 0.998442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 0.0129899 2.03541 399.763 -8.32472 100.009 +EDGE_SE3:QUAT 1404 1454 -0.0665629 -2.90613 -0.112797 0.0371099 -0.0011934 -0.0217952 0.999073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.449 0.00158078 -0.110713 399.586 -11.1314 100.366 +EDGE_SE3:QUAT 1405 1455 -0.145496 -3.14114 -0.037312 0.0253324 0.0010927 -0.0148227 0.999569 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.747 0.00460615 0.771166 399.807 -7.59426 100.172 +EDGE_SE3:QUAT 1406 1456 -0.0680009 -2.96203 -0.153302 0.0340074 0.0083277 -0.00855221 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.636 0.0291651 4.33486 399.624 -10.1803 100.391 +EDGE_SE3:QUAT 1407 1457 -0.0451566 -3.15697 -0.0886921 0.0360998 -0.00662781 0.0145795 0.99922 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.549 -0.0263508 -3.62575 399.59 -10.8025 100.405 +EDGE_SE3:QUAT 1408 1458 -0.0171086 -3.13116 0.0238625 0.0344566 -0.00544447 -0.00476674 0.99938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.0178402 -2.621 399.632 -10.3354 100.374 +EDGE_SE3:QUAT 1409 1459 0.0447583 -2.92111 -0.177546 0.0364789 0.00421004 -0.0299472 0.998877 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.51 0.0217268 2.75614 399.591 -10.912 100.328 +EDGE_SE3:QUAT 1410 1460 0.0488749 -3.11124 0.110536 0.0216099 -0.0111298 -0.0400819 0.998901 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.94 -0.027803 -5.03671 399.814 -6.57077 100.055 +EDGE_SE3:QUAT 1411 1461 -0.000562506 -3.08526 -0.152169 0.0272351 0.00205961 0.0372611 0.998932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 0.000128653 0.419374 399.776 -8.18472 100.085 +EDGE_SE3:QUAT 1412 1462 0.0858479 -3.06055 -0.0716978 0.0416325 -0.00547897 0.0560696 0.997543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.402 -0.0357301 -4.12708 399.461 -12.4219 100.246 +EDGE_SE3:QUAT 1413 1463 -0.0917391 -3.07495 -0.200095 0.0237456 -0.00319273 -0.0197217 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.783 -0.00560364 -1.31413 399.827 -7.13459 100.136 +EDGE_SE3:QUAT 1414 1464 0.0346657 -2.9515 -0.0695061 0.0307788 -0.00494674 0.0197037 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.664 -0.0178313 -2.83447 399.705 -9.20965 100.266 +EDGE_SE3:QUAT 1415 1465 0.0982136 -2.79815 0.100074 0.0274241 0.00104301 -0.00915035 0.999581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 0.00420345 0.671638 399.774 -8.2223 100.218 +EDGE_SE3:QUAT 1416 1466 0.00521197 -3.18371 -0.0845621 0.0411794 0.000622618 0.0189258 0.998972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.322 -0.00385741 -0.15656 399.491 -12.3464 100.473 +EDGE_SE3:QUAT 1417 1467 0.0820985 -3.02064 -0.134152 0.0390432 0.00243478 -0.0131408 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.403 0.0132718 1.52325 399.54 -11.6977 100.446 +EDGE_SE3:QUAT 1418 1468 -0.0615935 -3.16019 -0.120833 0.0350558 0.00340436 0.0195292 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 0.00735416 1.28918 399.627 -10.524 100.336 +EDGE_SE3:QUAT 1419 1469 -0.113872 -3.01411 -0.22652 0.0315242 0.00189347 0.00693157 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 0.00461459 0.814794 399.701 -9.4552 100.295 +EDGE_SE3:QUAT 1420 1470 0.128669 -3.06275 -0.116707 0.0343782 -0.000417296 -0.019861 0.999211 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.527 0.00325757 0.201103 399.645 -10.3097 100.315 +EDGE_SE3:QUAT 1421 1471 -0.02931 -3.20346 -0.0236705 0.0290932 -0.00899941 -0.0157096 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 -0.0255825 -4.22212 399.715 -8.7513 100.281 +EDGE_SE3:QUAT 1422 1472 -0.106077 -2.9925 -0.0624821 0.0367908 0.00415516 0.0195436 0.999123 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.471 0.0103576 1.64321 399.588 -11.0464 100.377 +EDGE_SE3:QUAT 1423 1473 -0.0239414 -3.02144 0.0058184 0.0355125 -0.00139953 0.0348345 0.998761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.507 -0.0132662 -1.43989 399.62 -10.6392 100.262 +EDGE_SE3:QUAT 1424 1474 0.190346 -3.02244 -0.130642 0.0366045 -0.000879673 -0.00809968 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.464 -0.00104662 -0.261473 399.598 -10.9755 100.396 +EDGE_SE3:QUAT 1425 1475 0.070112 -3.16877 -0.0659235 0.0242106 -0.00282573 -0.0385227 0.99896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 -0.0025359 -0.851024 399.822 -7.28459 100.031 +EDGE_SE3:QUAT 1426 1476 -0.00797889 -2.97364 0.0134975 0.028702 -0.00156683 0.0218639 0.999348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.00789143 -1.15889 399.751 -8.60078 100.203 +EDGE_SE3:QUAT 1427 1477 0.0392187 -2.95795 -0.0517485 0.0323817 0.00557564 -0.0101361 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.0195246 2.98219 399.672 -9.69743 100.328 +EDGE_SE3:QUAT 1428 1478 -0.0164042 -3.24258 0.202607 0.0325589 -0.0017282 0.0083378 0.999434 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 -0.00732108 -1.02606 399.681 -9.75961 100.314 +EDGE_SE3:QUAT 1429 1479 0.0770042 -3.15714 -0.134491 0.0382303 0.00305562 -0.00646365 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.43 0.0134122 1.674 399.557 -11.4565 100.442 +EDGE_SE3:QUAT 1430 1480 0.232111 -3.0744 -0.0264087 0.0274562 0.00044157 -0.0130733 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 0.00316452 0.435903 399.774 -8.23282 100.209 +EDGE_SE3:QUAT 1431 1481 -0.122164 -3.07109 -0.138505 0.0330505 0.00140458 -0.0194647 0.999263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 0.00872719 1.08718 399.671 -9.90478 100.293 +EDGE_SE3:QUAT 1432 1482 -0.0694643 -3.14477 -0.0191628 0.0227133 -0.00527509 0.0107554 0.99967 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.835 -0.0124983 -2.78291 399.834 -6.80051 100.164 +EDGE_SE3:QUAT 1433 1483 -0.163045 -3.05614 -0.126269 0.0329266 0.00659984 0.0289694 0.999016 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 0.0170185 2.72246 399.66 -9.91148 100.265 +EDGE_SE3:QUAT 1434 1484 0.197643 -2.96686 0.0603323 0.0352296 -0.00256763 0.0194358 0.999187 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.519 -0.0134639 -1.69264 399.624 -10.5527 100.342 +EDGE_SE3:QUAT 1435 1485 0.0384799 -3.15804 -0.153314 0.0351359 0.00472013 -0.00300793 0.999367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 0.0171745 2.42101 399.621 -10.5308 100.386 +EDGE_SE3:QUAT 1436 1486 0.0415012 -3.10148 0.0240764 0.0393706 0.00486854 0.00628314 0.999193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.406 0.0174144 2.2826 399.526 -11.8076 100.476 +EDGE_SE3:QUAT 1437 1487 0.108971 -3.07799 -0.110145 0.0368134 0.000360288 -0.0104532 0.999267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 0.0041427 0.410685 399.593 -11.036 100.396 +EDGE_SE3:QUAT 1438 1488 -0.044113 -2.99646 -0.104815 0.0345836 0.00328348 0.038945 0.998637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.523 0.0022323 0.830341 399.638 -10.397 100.211 +EDGE_SE3:QUAT 1439 1489 -0.149219 -3.24801 -0.0301921 0.0268849 -0.00684847 -0.0117184 0.999546 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.764 -0.0176095 -3.23305 399.765 -8.07793 100.233 +EDGE_SE3:QUAT 1440 1490 0.112179 -3.00944 -0.120006 0.0247528 -0.00423398 0.0070065 0.99966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.781 -0.011087 -2.21992 399.809 -7.41734 100.192 +EDGE_SE3:QUAT 1441 1491 -0.00439428 -3.01418 -0.203456 0.0296507 -0.00396373 -0.0150846 0.999439 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.00941086 -1.71168 399.731 -8.90332 100.25 +EDGE_SE3:QUAT 1442 1492 -0.109151 -3.22516 0.156737 0.0303992 0.00507073 0.0200989 0.999323 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.653 0.0123781 2.16601 399.714 -9.13611 100.251 +EDGE_SE3:QUAT 1443 1493 0.0220061 -3.01042 0.0186233 0.0275424 -0.00826385 0.0252639 0.999267 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.807 -0.0229286 -4.54548 399.743 -8.21706 100.219 +EDGE_SE3:QUAT 1444 1494 -0.0226628 -2.97448 -0.257686 0.0329691 -0.000450783 0.0313996 0.998963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 -0.00816524 -0.845685 399.673 -9.88408 100.229 +EDGE_SE3:QUAT 1445 1495 -0.0831201 -3.0404 -0.139814 0.0259922 -0.0112961 0.0141733 0.999498 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.911 -0.0279012 -5.8675 399.745 -7.76067 100.277 +EDGE_SE3:QUAT 1446 1496 0.144303 -2.95004 -0.104787 0.0325529 0.00271584 0.0514359 0.998142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.00202438 0.34999 399.68 -9.79295 100.055 +EDGE_SE3:QUAT 1447 1497 0.164602 -3.18762 -0.201016 0.0386515 -0.00094303 -0.00465635 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.403 -0.00224849 -0.362942 399.552 -11.5877 100.446 +EDGE_SE3:QUAT 1448 1498 -0.0949916 -3.04431 0.0663403 0.0255842 -0.00753985 0.00267228 0.999641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.814 -0.0193787 -3.80947 399.781 -7.66762 100.236 +EDGE_SE3:QUAT 1449 1499 0.0579622 -3.126 0.048343 0.0368224 0.00199274 -0.0076759 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.465 0.0093264 1.16463 399.591 -11.0361 100.404 +EDGE_SE3:QUAT 1450 1500 -0.0122964 -3.03331 -0.137219 0.0245419 0.00102821 0.0205124 0.999488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 5.76486e-05 0.211686 399.819 -7.36508 100.139 +EDGE_SE3:QUAT 1451 1501 0.242926 -3.09036 0.0153387 0.0313985 -0.00542045 0.0155811 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 -0.0190862 -3.00106 399.691 -9.39756 100.295 +EDGE_SE3:QUAT 1452 1502 0.0371973 -3.00307 0.0262124 0.0328672 -0.00336421 -0.00656517 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 -0.00973458 -1.55103 399.672 -9.85908 100.327 +EDGE_SE3:QUAT 1453 1503 -0.0245438 -3.05885 -0.111534 0.0320078 -0.00786394 0.00618233 0.999438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 -0.0257233 -4.04786 399.667 -9.58622 100.349 +EDGE_SE3:QUAT 1454 1504 -0.166886 -3.13229 -0.0732931 0.0273097 0.000382985 -0.0238516 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 0.00454969 0.581928 399.776 -8.18879 100.168 +EDGE_SE3:QUAT 1455 1505 -0.163036 -3.03205 -0.00025729 0.0319469 0.0029934 -0.0505786 0.998205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 0.0178122 2.46051 399.687 -9.55236 100.064 +EDGE_SE3:QUAT 1456 1506 0.0771592 -3.10403 -0.138116 0.0358207 0.00682971 0.0136988 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.536 0.0218933 3.11643 399.598 -10.7573 100.395 +EDGE_SE3:QUAT 1457 1507 0.0484934 -2.98207 -0.164762 0.0174594 -0.00425032 0.0278185 0.999451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.909 -0.0079729 -2.41463 399.9 -5.21374 100.029 +EDGE_SE3:QUAT 1458 1508 0.0815976 -3.08308 -0.102886 0.0197315 0.00227991 -0.000241364 0.999803 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.851 0.00451251 1.14243 399.881 -5.9181 100.12 +EDGE_SE3:QUAT 1459 1509 0.156271 -2.99707 -0.191499 0.0339834 0.00524523 0.012504 0.99933 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 0.0154228 2.36483 399.643 -10.2019 100.348 +EDGE_SE3:QUAT 1460 1510 4.05521e-05 -3.04457 -0.124608 0.0380785 0.00799268 0.0153304 0.999125 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.487 0.0274449 3.64081 399.541 -11.4387 100.451 +EDGE_SE3:QUAT 1461 1511 0.0331207 -3.09185 -0.137245 0.0341452 0.00500154 0.00707578 0.999379 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.562 0.0156875 2.3533 399.641 -10.2442 100.361 +EDGE_SE3:QUAT 1462 1512 0.0908232 -3.0238 -0.101309 0.0355335 0.00724103 0.00545373 0.999327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.0248188 3.50065 399.601 -10.6599 100.411 +EDGE_SE3:QUAT 1463 1513 0.00864268 -3.04522 -0.123863 0.0411929 0.00857644 -0.0140909 0.999015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.435 0.0379584 4.63046 399.46 -12.321 100.547 +EDGE_SE3:QUAT 1464 1514 -0.0502985 -3.12814 -0.0510892 0.0288722 -0.00410798 0.0118741 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 -0.0133997 -2.258 399.743 -8.64806 100.25 +EDGE_SE3:QUAT 1465 1515 -0.00707759 -3.03875 -0.0285588 0.0278223 -0.00472894 -0.0298765 0.999155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 -0.00929258 -1.86252 399.76 -8.37266 100.154 +EDGE_SE3:QUAT 1466 1516 -0.208393 -3.0294 -0.0746222 0.0274987 0.000599365 -0.00907828 0.99958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 0.00300571 0.449201 399.773 -8.24549 100.219 +EDGE_SE3:QUAT 1467 1517 -0.08451 -3.04205 -0.0603531 0.030281 0.00187674 -0.0231876 0.999271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 0.00963234 1.35827 399.723 -9.07209 100.226 +EDGE_SE3:QUAT 1468 1518 -0.0505602 -2.99182 -0.0667217 0.0328962 -0.00449873 0.0224445 0.999197 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 -0.0185018 -2.68924 399.666 -9.84346 100.293 +EDGE_SE3:QUAT 1469 1519 -0.173974 -2.87874 -0.24046 0.0233474 -0.000928214 0.0203119 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 -0.00430207 -0.748162 399.836 -6.99898 100.124 +EDGE_SE3:QUAT 1470 1520 0.0793507 -3.09859 0.0506259 0.0265595 -0.0101733 0.013908 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.866 -0.0262612 -5.30631 399.746 -7.93482 100.269 +EDGE_SE3:QUAT 1471 1521 -0.0849729 -3.13148 -0.0183556 0.0296848 -0.00577933 -0.0216013 0.999309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0143297 -2.50177 399.724 -8.92661 100.237 +EDGE_SE3:QUAT 1472 1522 0.0875691 -3.04439 -0.301831 0.0233909 0.000777674 -0.0330359 0.99918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 0.00527493 0.851668 399.835 -7.01144 100.057 +EDGE_SE3:QUAT 1473 1523 0.0440002 -2.88071 0.0616479 0.0317098 -0.00774858 0.00259076 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0248137 -3.92089 399.674 -9.5027 100.344 +EDGE_SE3:QUAT 1474 1524 -0.0292739 -3.01869 -0.136298 0.038297 -0.00518052 -0.00520944 0.999239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.444 -0.0185024 -2.46733 399.55 -11.4854 100.455 +EDGE_SE3:QUAT 1475 1525 0.0348511 -3.03297 -0.307273 0.0302192 -0.00320484 -0.016096 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.00693555 -1.30902 399.722 -9.07217 100.254 +EDGE_SE3:QUAT 1476 1526 0.200722 -3.03673 -0.198971 0.0300501 -0.0009377 -0.00267266 0.999544 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 -0.00233376 -0.420294 399.729 -9.01145 100.271 +EDGE_SE3:QUAT 1477 1527 0.0704842 -3.01271 -0.103731 0.0323282 -0.000396102 0.000696159 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 -0.00142307 -0.211363 399.686 -9.69333 100.314 +EDGE_SE3:QUAT 1478 1528 -0.26117 -3.01328 -0.100638 0.029522 0.00256531 0.0141657 0.99946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 0.00520499 1.0306 399.736 -8.86021 100.245 +EDGE_SE3:QUAT 1479 1529 -0.0738299 -2.8944 -0.0195218 0.0214458 0.00308303 0.00242823 0.999762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 0.00642464 1.50968 399.858 -6.43361 100.144 +EDGE_SE3:QUAT 1480 1530 -0.0702237 -3.33992 -0.048626 0.0289691 -0.00753594 -0.0072293 0.999526 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.732 -0.0213174 -3.63997 399.726 -8.69688 100.284 +EDGE_SE3:QUAT 1481 1531 0.0471118 -2.96882 -0.0471514 0.0365308 -0.000964838 -0.0154256 0.999213 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.466 0.000596556 -0.143807 399.599 -10.9553 100.377 +EDGE_SE3:QUAT 1482 1532 0.132377 -2.97142 -0.0937641 0.0300766 0.00809032 0.0158719 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 0.0230974 3.75531 399.704 -9.04364 100.287 +EDGE_SE3:QUAT 1483 1533 0.0480049 -3.01471 0.0816344 0.0264187 0.00355334 -0.000877041 0.999644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 0.00948115 1.78953 399.786 -7.92198 100.218 +EDGE_SE3:QUAT 1484 1534 0.093426 -3.06443 -0.0992595 0.0268062 -0.00850032 -0.0130862 0.999519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 -0.022475 -4.0372 399.757 -8.06012 100.245 +EDGE_SE3:QUAT 1485 1535 -0.0459628 -3.07576 -0.232439 0.0330079 -0.000310732 -0.0032348 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.564 -0.000319142 -0.0911713 399.673 -9.89718 100.326 +EDGE_SE3:QUAT 1486 1536 -0.142974 -3.23039 -0.112534 0.0318465 -0.00624944 0.0163292 0.99934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.657 -0.0218437 -3.43363 399.679 -9.52803 100.309 +EDGE_SE3:QUAT 1487 1537 0.0274043 -2.9532 -0.231942 0.0352694 -0.00204369 0.0292079 0.998949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.517 -0.013927 -1.63765 399.624 -10.5635 100.294 +EDGE_SE3:QUAT 1488 1538 0.0370613 -2.91405 -0.0548517 0.0360864 0.00388295 0.00847847 0.999305 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 0.011966 1.75565 399.604 -10.8252 100.393 +EDGE_SE3:QUAT 1489 1539 -0.213618 -3.31568 -0.177221 0.0319589 0.00239878 -0.000395852 0.999486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.599 0.00772896 1.2059 399.691 -9.58244 100.31 +EDGE_SE3:QUAT 1490 1540 -0.241457 -3.04921 -0.0988095 0.0344922 0.000437711 0.00250923 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.524 0.000910002 0.166711 399.643 -10.3417 100.356 +EDGE_SE3:QUAT 1491 1541 0.095635 -3.09193 -0.0365968 0.0276585 -0.00326414 -0.0167549 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 -0.00668106 -1.35261 399.767 -8.30554 100.207 +EDGE_SE3:QUAT 1492 1542 0.0129842 -2.97485 -0.0496116 0.0375911 0.0113725 -0.0114585 0.999163 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 0.0432113 5.93972 399.522 -11.2396 100.507 +EDGE_SE3:QUAT 1493 1543 0.0162058 -3.13924 -0.0190449 0.0303299 0.0038453 -0.00789749 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 0.0128617 2.06476 399.718 -9.08842 100.281 +EDGE_SE3:QUAT 1494 1544 -0.177366 -3.04872 -0.0104906 0.0422566 -0.00499554 0.00606479 0.999076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.323 -0.0229181 -2.64762 399.454 -12.6588 100.551 +EDGE_SE3:QUAT 1495 1545 -0.0858572 -2.92129 -0.297449 0.0333685 -0.00768385 0.00398563 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 -0.0260913 -3.91865 399.642 -9.99734 100.375 +EDGE_SE3:QUAT 1496 1546 0.0849363 -3.10063 -0.118535 0.0266158 0.0120888 0.039506 0.998792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.862 0.0351111 5.40353 399.734 -8.07713 100.144 +EDGE_SE3:QUAT 1497 1547 0.00887894 -2.96862 -0.172428 0.0277488 -0.00444856 0.0138828 0.999509 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 -0.0138813 -2.45365 399.76 -8.30886 100.228 +EDGE_SE3:QUAT 1498 1548 -0.0369421 -3.09309 -0.0425388 0.0302312 -0.00148648 -0.00220965 0.999539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.637 -0.00409014 -0.702564 399.725 -9.06583 100.275 +EDGE_SE3:QUAT 1499 1549 0.0949579 -3.08466 -0.209415 0.0307339 -0.00570122 0.00269438 0.999508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 -0.0178579 -2.89818 399.703 -9.21198 100.306 +EDGE_SE3:QUAT 1500 1550 0.00156628 -3.06113 -0.0297818 0.031082 -0.00708516 0.0101728 0.99944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.687 -0.0229815 -3.72958 399.689 -9.30457 100.317 +EDGE_SE3:QUAT 1501 1551 0.0950155 -3.05002 -0.132304 0.0337691 -0.00458961 0.00979113 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 -0.0172786 -2.49079 399.649 -10.1155 100.349 +EDGE_SE3:QUAT 1502 1552 0.0328266 -3.09963 -0.141513 0.0249527 -0.00204044 -0.0255839 0.999359 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 -0.0019805 -0.636177 399.812 -7.49471 100.123 +EDGE_SE3:QUAT 1503 1553 0.140479 -3.04174 -0.105443 0.0364327 0.000714094 -0.000521502 0.999336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 0.00273263 0.368016 399.602 -10.9225 100.399 +EDGE_SE3:QUAT 1504 1554 -0.112078 -3.14015 -0.21846 0.0308016 0.000673476 -0.0120504 0.999453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.00433073 0.559032 399.715 -9.23467 100.271 +EDGE_SE3:QUAT 1505 1555 0.0407665 -2.93725 -0.290733 0.03329 -0.00444288 0.00678846 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 -0.0160057 -2.35487 399.659 -9.97497 100.343 +EDGE_SE3:QUAT 1506 1556 0.183703 -2.96895 -0.050741 0.0334355 -0.00197132 -0.0375072 0.998735 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.552 0.00178986 -0.231611 399.663 -10.0422 100.196 +EDGE_SE3:QUAT 1507 1557 0.245295 -3.00013 -0.270078 0.0295973 -0.00137134 -0.0223234 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.65 -0.000157439 -0.288578 399.737 -8.88215 100.214 +EDGE_SE3:QUAT 1508 1558 -0.0636927 -2.97486 -0.216055 0.0205993 0.000468208 -0.00370276 0.999781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 0.00127581 0.27977 399.873 -6.17814 100.126 +EDGE_SE3:QUAT 1509 1559 0.158999 -3.20143 -0.166864 0.0328575 0.00568713 -0.00656519 0.999422 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0196745 2.97046 399.663 -9.84367 100.344 +EDGE_SE3:QUAT 1510 1560 -0.0322777 -3.15676 -0.114948 0.0317462 -0.000519959 -0.0130852 0.99941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 0.000989028 -0.0105587 399.698 -9.5207 100.285 +EDGE_SE3:QUAT 1511 1561 0.321175 -3.04157 -0.108344 0.0291024 0.00222985 0.0109022 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.665 0.00470211 0.923658 399.744 -8.73199 100.245 +EDGE_SE3:QUAT 1512 1562 0.0674057 -3.10072 -0.0309059 0.0258013 -0.00880942 0.00694876 0.999604 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.84 -0.0226814 -4.51074 399.769 -7.72409 100.251 +EDGE_SE3:QUAT 1513 1563 -0.0832783 -3.01555 -0.0727245 0.0305563 -0.00475775 -0.0225183 0.999268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.645 -0.0109584 -1.96322 399.712 -9.18445 100.242 +EDGE_SE3:QUAT 1514 1564 0.00619854 -3.11583 0.00291023 0.034017 -0.00798545 0.00141527 0.999388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.621 -0.0273312 -4.01835 399.627 -10.1953 100.392 +EDGE_SE3:QUAT 1515 1565 0.158505 -3.06267 0.0192168 0.0263253 0.00481435 -0.0168396 0.9995 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 0.0141524 2.67125 399.782 -7.87847 100.198 +EDGE_SE3:QUAT 1516 1566 0.0508353 -3.05966 -0.196511 0.046176 -0.000393628 -0.0127364 0.998852 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.147 0.00361471 0.156193 399.36 -13.8394 100.624 +EDGE_SE3:QUAT 1517 1567 0.0834154 -3.07007 -0.131744 0.0325205 0.000370774 0.0207522 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 -0.00317968 -0.219584 399.683 -9.75322 100.274 +EDGE_SE3:QUAT 1518 1568 0.047666 -3.10564 -0.0815679 0.029332 -0.0021347 -0.01029 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 -0.00454125 -0.885393 399.74 -8.80029 100.25 +EDGE_SE3:QUAT 1519 1569 0.0416736 -3.09731 -0.264139 0.0290602 0.00869898 0.0236453 0.99926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.0239726 3.93264 399.719 -8.75493 100.244 +EDGE_SE3:QUAT 1520 1570 0.139476 -2.90002 -0.134585 0.0329631 0.00177513 0.00978166 0.999407 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.568 0.00374962 0.693239 399.673 -9.88713 100.318 +EDGE_SE3:QUAT 1521 1571 0.0682854 -2.98598 -0.353151 0.0366974 0.0109036 -0.00670192 0.999244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.625 0.0403991 5.59498 399.547 -10.9839 100.486 +EDGE_SE3:QUAT 1522 1572 -0.01798 -2.99719 -0.204302 0.0321646 -0.0029137 -0.0334199 0.998919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.588 -0.00261373 -0.809527 399.687 -9.66558 100.202 +EDGE_SE3:QUAT 1523 1573 -0.0701957 -3.22193 -0.0141426 0.0269592 0.00128241 0.002654 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.711 0.00307368 0.597865 399.781 -8.08547 100.218 +EDGE_SE3:QUAT 1524 1574 0.0515603 -3.02432 -0.246666 0.0293262 0.0029217 -0.0711182 0.997032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.697 0.0173426 2.70237 399.735 -8.75907 99.7688 +EDGE_SE3:QUAT 1525 1575 -0.0498292 -3.0713 -0.0289877 0.031483 -0.0012369 -0.020359 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 0.000138427 -0.233271 399.702 -9.44589 100.256 +EDGE_SE3:QUAT 1526 1576 0.148204 -3.11252 -0.122259 0.027808 -0.0014337 0.0144618 0.999508 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 -0.00612546 -0.957444 399.767 -8.33524 100.213 +EDGE_SE3:QUAT 1527 1577 0.057824 -3.09071 -0.085049 0.0201479 0.00420431 -0.0180856 0.999625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.866 0.00924883 2.31954 399.871 -6.02795 100.103 +EDGE_SE3:QUAT 1528 1578 0.0276849 -2.89431 -0.0889154 0.0256046 0.00400494 -0.0297512 0.999221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.771 0.0128961 2.45677 399.796 -7.65571 100.123 +EDGE_SE3:QUAT 1529 1579 0.0257364 -3.1602 0.056284 0.0255108 0.000290425 0.026696 0.999318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 -0.00272476 -0.263402 399.805 -7.65321 100.124 +EDGE_SE3:QUAT 1530 1580 0.205012 -3.06721 -0.103237 0.0339771 0.0101126 -0.00415223 0.999363 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.0345911 5.13754 399.612 -10.1762 100.418 +EDGE_SE3:QUAT 1531 1581 -0.0751571 -3.10181 -0.069928 0.0287417 -0.00537304 0.0221885 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 -0.0176329 -3.06626 399.739 -8.59504 100.223 +EDGE_SE3:QUAT 1532 1582 0.180332 -3.17757 -0.192242 0.0213044 0.00194831 -0.0240718 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.827 0.00605932 1.28088 399.862 -6.38101 100.082 +EDGE_SE3:QUAT 1533 1583 -0.178464 -2.93268 -0.171116 0.0337086 -0.000757977 0.031135 0.998946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 -0.00941875 -1.00756 399.658 -10.1037 100.246 +EDGE_SE3:QUAT 1534 1584 -0.0968383 -3.09195 -0.222963 0.0285851 4.54889e-05 0.00853914 0.999555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.00126437 -0.123686 399.755 -8.57221 100.238 +EDGE_SE3:QUAT 1535 1585 -0.0803853 -3.0655 -0.10692 0.0222781 0.0032714 -0.0200821 0.999545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.821 0.00876599 1.90284 399.846 -6.66883 100.118 +EDGE_SE3:QUAT 1536 1586 -0.124951 -3.0527 -0.0749644 0.0217352 0.0063026 -0.0258939 0.999409 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.876 0.0139265 3.48627 399.841 -6.48634 100.107 +EDGE_SE3:QUAT 1537 1587 0.0843247 -2.93162 -0.0166234 0.0289092 -0.00591863 -0.0114248 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.0158243 -2.7589 399.736 -8.68218 100.26 +EDGE_SE3:QUAT 1538 1588 -0.0354141 -3.07986 -0.0371913 0.0338769 -0.00113224 0.0265667 0.999072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -0.00970807 -1.10487 399.654 -10.1523 100.276 +EDGE_SE3:QUAT 1539 1589 0.0579006 -3.12999 -0.115683 0.0281348 0.00854358 0.0145033 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.766 0.0234664 4.02403 399.735 -8.46079 100.263 +EDGE_SE3:QUAT 1540 1590 0.0309525 -3.05556 -0.144786 0.0281313 0.0010743 -0.0283767 0.999201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.689 0.00731375 1.01511 399.762 -8.43101 100.159 +EDGE_SE3:QUAT 1541 1591 -0.0824848 -3.09321 -0.136869 0.0324581 -2.79951e-05 -0.00481444 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 0.000923054 0.0797429 399.684 -9.73236 100.314 +EDGE_SE3:QUAT 1542 1592 0.102397 -3.25193 -0.0840623 0.0276585 0.00524039 0.0373958 0.998904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 0.00987675 1.99501 399.761 -8.3352 100.103 +EDGE_SE3:QUAT 1543 1593 0.136431 -3.12683 -0.0761961 0.0249947 -0.00172459 -0.0526469 0.998299 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.749 0.00227568 -0.0710165 399.812 -7.5177 99.911 +EDGE_SE3:QUAT 1544 1594 -0.013614 -3.04535 -0.184227 0.0266501 -0.00110162 -0.0373356 0.998947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 0.00237437 0.0468163 399.786 -8.00229 100.074 +EDGE_SE3:QUAT 1545 1595 0.00857537 -3.14204 -0.0663572 0.0297956 0.00937609 0.013266 0.999424 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 0.0275174 4.44763 399.7 -8.95804 100.306 +EDGE_SE3:QUAT 1546 1596 0.152529 -2.94189 -0.138613 0.0339613 -0.00789076 -0.0275971 0.999011 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 -0.022735 -3.37702 399.632 -10.2262 100.305 +EDGE_SE3:QUAT 1547 1597 0.108353 -2.91482 -0.197133 0.025301 0.00423733 -0.000475802 0.999671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.767 0.0107599 2.1248 399.801 -7.58712 100.205 +EDGE_SE3:QUAT 1548 1598 -0.152337 -3.12747 -0.173032 0.0313568 -0.0092271 0.00412398 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0291337 -4.68843 399.671 -9.39278 100.354 +EDGE_SE3:QUAT 1549 1599 0.000407988 -3.12924 -0.276538 0.0294204 -0.000915396 -0.0237461 0.999285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 0.00142109 -0.0381369 399.74 -8.82748 100.203 +EDGE_SE3:QUAT 1550 1600 0.297469 -3.02632 -0.0428668 0.0393091 0.0065454 0.00663131 0.999184 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.431 0.0241044 3.11209 399.52 -11.7912 100.487 +EDGE_SE3:QUAT 1551 1601 -0.12387 -3.21715 -0.148698 0.0266462 0.0011029 -0.00589128 0.999627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 0.00375387 0.645249 399.786 -7.98974 100.211 +EDGE_SE3:QUAT 1552 1602 -0.155186 -2.95413 -0.126659 0.0282112 -0.0099202 -0.0110947 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.798 -0.0280978 -4.7697 399.723 -8.4802 100.292 +EDGE_SE3:QUAT 1553 1603 0.0382022 -3.02486 -0.0846732 0.0266259 -0.00325768 -0.000934776 0.99964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 -0.00855002 -1.61293 399.783 -7.98535 100.22 +EDGE_SE3:QUAT 1554 1604 0.0467163 -3.06866 -0.148987 0.0394581 0.000669007 0.0194869 0.999031 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.377 -0.00343193 -0.127133 399.533 -11.8316 100.429 +EDGE_SE3:QUAT 1555 1605 0.0791336 -3.02089 -0.121887 0.0277046 -0.00487131 -0.0114272 0.999539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.0121507 -2.24393 399.761 -8.31909 100.232 +EDGE_SE3:QUAT 1556 1606 -0.142713 -2.99072 -0.305487 0.0340287 -0.00246787 0.0208008 0.999201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.552 -0.0128029 -1.65672 399.649 -10.1929 100.311 +EDGE_SE3:QUAT 1557 1607 0.150274 -3.20286 0.00644862 0.0293349 -0.00403585 0.00834992 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.0129856 -2.16331 399.735 -8.78964 100.264 +EDGE_SE3:QUAT 1558 1608 -0.0379044 -2.85366 -0.0437557 0.0357752 -0.00862441 -0.00748879 0.999295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.576 -0.0298703 -4.14729 399.587 -10.7368 100.428 +EDGE_SE3:QUAT 1559 1609 -0.194397 -2.9518 -0.0592383 0.0258788 0.00678008 0.00443936 0.999632 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.789 0.0173103 3.31952 399.781 -7.76621 100.23 +EDGE_SE3:QUAT 1560 1610 -0.00375714 -3.02137 -0.0404717 0.0276691 0.00708351 0.00899742 0.999552 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 0.0189748 3.39025 399.751 -8.30943 100.255 +EDGE_SE3:QUAT 1561 1611 -0.0358943 -3.12345 -0.00474627 0.0323483 0.00800924 0.0276126 0.999063 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 0.0225576 3.46295 399.663 -9.74367 100.275 +EDGE_SE3:QUAT 1562 1612 0.0659228 -2.9928 -0.159089 0.0359903 -0.000829806 0.0193245 0.999165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.486 -0.00789425 -0.831356 399.611 -10.7875 100.353 +EDGE_SE3:QUAT 1563 1613 -0.17369 -3.1001 -0.264821 0.0250485 0.00185779 -0.00658387 0.999663 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 0.00542509 1.02728 399.81 -7.50973 100.187 +EDGE_SE3:QUAT 1564 1614 -0.0166508 -3.03011 -0.208047 0.0256834 -0.00223226 -0.0224023 0.999417 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.00287269 -0.769879 399.801 -7.71307 100.15 +EDGE_SE3:QUAT 1565 1615 -0.0967041 -2.97105 -0.11496 0.0260537 -0.00355698 0.0197353 0.999459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 -0.011336 -2.08532 399.79 -7.79959 100.176 +EDGE_SE3:QUAT 1566 1616 0.0338935 -3.19303 -0.157456 0.0293342 0.00185818 0.0099 0.999519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.00378063 0.754103 399.741 -8.80025 100.25 +EDGE_SE3:QUAT 1567 1617 -0.0162452 -3.15712 -0.279401 0.0359892 -0.00106414 0.0184658 0.999181 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.487 -0.00849417 -0.929826 399.611 -10.7864 100.356 +EDGE_SE3:QUAT 1568 1618 -0.102844 -3.14731 -0.178781 0.0322671 0.000800891 0.0103186 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.584 0.000434606 0.200337 399.687 -9.6769 100.302 +EDGE_SE3:QUAT 1569 1619 0.0477148 -2.95365 -0.161581 0.028817 -0.00214684 -0.023425 0.999308 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 -0.00236836 -0.667252 399.749 -8.6523 100.196 +EDGE_SE3:QUAT 1570 1620 0.183173 -2.89732 -0.145997 0.040375 0.00225059 0.0115361 0.999115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.351 0.00536173 0.844215 399.509 -12.108 100.478 +EDGE_SE3:QUAT 1571 1621 0.137378 -3.17708 -0.200221 0.0249109 -0.00574885 -0.000802826 0.999673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.794 -0.0142687 -2.86115 399.801 -7.47127 100.209 +EDGE_SE3:QUAT 1572 1622 0.0461384 -2.98229 -0.0882955 0.0254694 -0.00184906 -0.0309456 0.999195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 -0.00074009 -0.450548 399.804 -7.65099 100.1 +EDGE_SE3:QUAT 1573 1623 0.0796928 -3.21416 -0.0475025 0.0369818 -0.00108504 -0.0282597 0.998916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.453 0.00372637 0.0851397 399.589 -11.0945 100.331 +EDGE_SE3:QUAT 1574 1624 0.222315 -3.06482 0.0530381 0.0304739 -0.00458926 -0.0179072 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.647 -0.0111517 -1.96484 399.714 -9.15449 100.258 +EDGE_SE3:QUAT 1575 1625 -0.108282 -3.08746 -0.165596 0.0296691 0.00253525 -0.0131797 0.99947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 0.00962216 1.50101 399.733 -8.89019 100.253 +EDGE_SE3:QUAT 1576 1626 0.105345 -3.16815 0.0341791 0.0267257 0.000150975 -0.0135151 0.999551 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 0.00232572 0.292084 399.786 -8.01469 100.196 +EDGE_SE3:QUAT 1577 1627 0.00948316 -3.042 -0.148562 0.0394623 0.00184197 -0.00439398 0.99921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.383 0.00858226 1.02368 399.531 -11.8278 100.468 +EDGE_SE3:QUAT 1578 1628 -0.0972393 -3.00185 -0.170597 0.0368758 -0.00165136 0.0279448 0.998928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.468 -0.013282 -1.442 399.59 -11.0472 100.335 +EDGE_SE3:QUAT 1579 1629 0.0342073 -2.9237 -0.121685 0.0313073 -0.00340074 -0.0250712 0.99919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 -0.00600124 -1.22723 399.702 -9.40547 100.237 +EDGE_SE3:QUAT 1580 1630 0.138625 -2.80367 -0.0962346 0.0341115 0.0115015 0.0294547 0.998918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 0.0381321 5.13939 399.603 -10.2939 100.342 +EDGE_SE3:QUAT 1581 1631 -0.133626 -2.93352 -0.0487959 0.0305735 -0.00375189 -0.0091133 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 -0.00994517 -1.70717 399.714 -9.17445 100.281 +EDGE_SE3:QUAT 1582 1632 0.00200666 -3.12127 -0.0231594 0.0314772 0.00476519 -0.000703491 0.999493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 0.0150932 2.39395 399.694 -9.43726 100.313 +EDGE_SE3:QUAT 1583 1633 0.0254032 -3.03705 -0.191644 0.0345573 -0.00524749 0.00239983 0.999386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.0185604 -2.67092 399.631 -10.3577 100.377 +EDGE_SE3:QUAT 1584 1634 -0.0988332 -3.11012 0.0885873 0.0409109 0.00451681 -0.0100088 0.999102 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.364 0.0213394 2.50058 399.489 -12.2534 100.509 +EDGE_SE3:QUAT 1585 1635 -0.03036 -3.16518 -0.276968 0.0318844 -0.00703389 -0.045844 0.998415 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.625 -0.0154722 -2.63109 399.679 -9.62767 100.119 +EDGE_SE3:QUAT 1586 1636 0.00720786 -3.09961 -0.0169409 0.0323875 0.00603648 0.0248564 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 0.0154918 2.53113 399.672 -9.74151 100.273 +EDGE_SE3:QUAT 1587 1637 0.0104427 -3.20077 -0.143173 0.0331917 0.00217631 0.0232712 0.999176 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.002154 0.623354 399.668 -9.96299 100.278 +EDGE_SE3:QUAT 1588 1638 -0.02948 -2.82963 -0.0371475 0.0245093 0.00364543 0.0297207 0.999251 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 0.00578357 1.38346 399.815 -7.3732 100.098 +EDGE_SE3:QUAT 1589 1639 0.0658815 -3.01629 -0.155712 0.0216623 -0.00377291 0.00121277 0.999757 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 -0.00825211 -1.90151 399.853 -6.49603 100.151 +EDGE_SE3:QUAT 1590 1640 0.181601 -3.23754 -0.0428018 0.0338349 -0.00183576 -0.0130256 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.544 -0.0032588 -0.652481 399.655 -10.1497 100.328 +EDGE_SE3:QUAT 1591 1641 0.076053 -3.28055 -0.0558072 0.0306525 -0.00816586 -0.00962067 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 -0.0242946 -3.90304 399.692 -9.20585 100.316 +EDGE_SE3:QUAT 1592 1642 -0.152447 -3.21976 -0.0570661 0.0312543 -0.00182058 -0.0376958 0.998799 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 0.00167077 -0.201996 399.706 -9.38767 100.152 +EDGE_SE3:QUAT 1593 1643 0.0409769 -3.00659 -0.205898 0.0257895 0.00164026 -0.015568 0.999545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.00617403 1.0603 399.799 -7.72939 100.178 +EDGE_SE3:QUAT 1594 1644 -0.153103 -2.8164 0.0547661 0.0393225 0.00667665 -0.0142191 0.999103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.453 0.0292655 3.66912 399.517 -11.7675 100.479 +EDGE_SE3:QUAT 1595 1645 -0.00201381 -3.14387 -0.0924819 0.0285965 -0.000121323 -0.0207556 0.999376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.00303694 0.295381 399.755 -8.57655 100.202 +EDGE_SE3:QUAT 1596 1646 -0.038192 -3.05168 -0.0614017 0.0262849 -0.00250163 0.0216935 0.999416 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 -0.00918367 -1.59157 399.79 -7.87231 100.167 +EDGE_SE3:QUAT 1597 1647 0.126749 -3.1517 0.0630315 0.0350602 0.000617749 0.00156098 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.509 0.00177788 0.275709 399.631 -10.5118 100.369 +EDGE_SE3:QUAT 1598 1648 -0.0975346 -2.98387 -0.0200672 0.0376256 -0.00180642 -0.00999821 0.99924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.436 -0.00398347 -0.676383 399.574 -11.2834 100.416 +EDGE_SE3:QUAT 1599 1649 0.0902319 -3.21333 -0.176788 0.0304553 -0.0052908 -0.0370574 0.998835 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 -0.010296 -1.96334 399.712 -9.17333 100.154 +EDGE_SE3:QUAT 1600 1650 0.0113906 -2.93396 -0.0407956 0.0281798 0.00534008 -0.00158884 0.999587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 0.0152103 2.69526 399.75 -8.44828 100.258 +EDGE_SE3:QUAT 1601 1651 -0.0993613 -2.90503 -0.0932279 0.0248068 -0.00325643 0.0112658 0.999623 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.771 -0.009201 -1.79486 399.811 -7.43234 100.18 +EDGE_SE3:QUAT 1602 1652 0.0681438 -3.04095 -0.297807 0.0262633 0.0038759 0.0110482 0.999586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.00889688 1.76255 399.787 -7.88475 100.204 +EDGE_SE3:QUAT 1603 1653 -0.0878251 -3.15728 -0.148614 0.0379052 0.00195088 0.00878276 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.428 0.00489142 0.774466 399.568 -11.3669 100.425 +EDGE_SE3:QUAT 1604 1654 0.0712583 -3.05481 -0.235197 0.0256873 -0.00404443 -0.0214876 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.75 -0.00799816 -1.68917 399.796 -7.7214 100.161 +EDGE_SE3:QUAT 1605 1655 -0.0625302 -2.9818 -0.0786953 0.0357438 0.000615749 -0.0340236 0.998781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 0.0106542 1.03631 399.616 -10.7141 100.27 +EDGE_SE3:QUAT 1606 1656 0.0938803 -3.08946 -0.413693 0.0209219 -0.00142704 -0.0146822 0.999672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.826 -0.001729 -0.528835 399.868 -6.27959 100.111 +EDGE_SE3:QUAT 1607 1657 0.0369366 -3.05858 -0.198546 0.0290393 -0.00404366 0.0416154 0.998703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.704 -0.0165966 -2.74198 399.738 -8.6763 100.098 +EDGE_SE3:QUAT 1608 1658 0.00161531 -3.15978 -0.0607119 0.0332348 -0.00245681 0.00932752 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 -0.0100779 -1.41306 399.666 -9.9603 100.328 +EDGE_SE3:QUAT 1609 1659 -0.0103481 -3.15779 -0.0547871 0.0295006 -0.00543389 -0.0226902 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 -0.0129612 -2.31225 399.728 -8.87126 100.226 +EDGE_SE3:QUAT 1610 1660 -0.0548329 -3.13305 -0.153966 0.0260955 0.00519625 -0.0150799 0.999532 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.77 0.0147521 2.83239 399.784 -7.80998 100.203 +EDGE_SE3:QUAT 1611 1661 -0.0671868 -3.33123 -0.0408857 0.0349616 -0.00850817 -0.0234151 0.999078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.581 -0.0264351 -3.75703 399.607 -10.5213 100.355 +EDGE_SE3:QUAT 1612 1662 0.140147 -2.82919 -0.171349 0.0359887 0.00195534 -0.0104676 0.999295 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 0.00962456 1.20239 399.61 -10.7856 100.381 +EDGE_SE3:QUAT 1613 1663 -0.0396074 -2.93462 -0.184178 0.029501 -0.000526943 0.00442667 0.999555 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.653 -0.00231845 -0.341593 399.739 -8.84599 100.259 +EDGE_SE3:QUAT 1614 1664 -0.110135 -3.04507 0.0684345 0.0404717 0.00318728 -0.0383776 0.998438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.38 0.0237869 2.52044 399.502 -12.1093 100.359 +EDGE_SE3:QUAT 1615 1665 -0.00200346 -3.0994 0.052167 0.0219187 0.00472538 0.00229929 0.999746 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.836 0.0102253 2.3316 399.847 -6.57585 100.159 +EDGE_SE3:QUAT 1616 1666 -0.00590666 -2.91518 -0.0742091 0.0290887 0.000413083 0.013576 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.00109718 -0.030514 399.746 -8.72431 100.235 +EDGE_SE3:QUAT 1617 1667 0.0460345 -3.09381 -0.0892004 0.0370252 0.00925158 -0.00560803 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.57 0.0349104 4.74602 399.554 -11.0872 100.47 +EDGE_SE3:QUAT 1618 1668 -0.0160461 -3.08989 -0.20474 0.0201903 0.00598473 -0.0331817 0.999227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.899 0.0121043 3.39068 399.862 -6.01655 100.042 +EDGE_SE3:QUAT 1619 1669 0.0475918 -3.05535 -0.120123 0.0331313 0.00289476 -0.0134758 0.999356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 0.0122533 1.71356 399.667 -9.92616 100.319 +EDGE_SE3:QUAT 1620 1670 0.160021 -3.10133 -0.0992102 0.028776 -0.00938922 -0.00992676 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.774 -0.0268805 -4.52058 399.717 -8.64622 100.297 +EDGE_SE3:QUAT 1621 1671 -0.175509 -2.99319 0.148156 0.0266087 0.00685951 0.0138299 0.999527 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 0.01733 3.20667 399.77 -7.99818 100.223 +EDGE_SE3:QUAT 1622 1672 0.0694192 -3.16129 -0.0963938 0.0332764 -0.00540972 -0.0152912 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 -0.0152355 -2.39659 399.657 -9.99374 100.326 +EDGE_SE3:QUAT 1623 1673 -0.0428872 -2.81883 -0.291116 0.0311206 -0.00362823 -0.00583842 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 -0.010267 -1.70356 399.704 -9.33569 100.296 +EDGE_SE3:QUAT 1624 1674 -0.0375019 -3.02594 -0.0849859 0.0281321 -0.00961271 0.011973 0.999486 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.815 -0.0268532 -5.00618 399.724 -8.4114 100.292 +EDGE_SE3:QUAT 1625 1675 -0.0517798 -3.06874 -0.308725 0.0324027 -0.0045526 -0.0137182 0.99937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.0122553 -2.00726 399.677 -9.72811 100.308 +EDGE_SE3:QUAT 1626 1676 0.0643848 -3.18905 -0.188479 0.0350804 0.000780081 -0.0211225 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.512 0.00782981 0.833807 399.63 -10.5151 100.326 +EDGE_SE3:QUAT 1627 1677 -0.115431 -3.06355 -0.11944 0.0304085 -0.00168359 -0.0168976 0.999393 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 -0.0020237 -0.532702 399.722 -9.12442 100.25 +EDGE_SE3:QUAT 1628 1678 -0.110637 -3.08698 -0.0296284 0.0364759 -0.00367845 0.00710214 0.999303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.489 -0.0150784 -1.99242 399.595 -10.9299 100.405 +EDGE_SE3:QUAT 1629 1679 0.15098 -2.99992 -0.0210215 0.0213397 -0.000652959 -0.0353767 0.999146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.818 0.00182938 0.126721 399.863 -6.4064 100.012 +EDGE_SE3:QUAT 1630 1680 0.0590887 -2.98946 -0.289894 0.0290626 -0.00883937 -0.0197861 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 -0.0247556 -4.07073 399.717 -8.74916 100.263 +EDGE_SE3:QUAT 1631 1681 -0.0725235 -3.25599 -0.0819169 0.024812 -0.000298694 -0.00651325 0.999671 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 6.13581e-05 -0.0523158 399.815 -7.44174 100.18 +EDGE_SE3:QUAT 1632 1682 0.107594 -3.05843 -0.183283 0.0267608 0.00564849 -0.00805941 0.999593 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 0.0157664 2.95201 399.772 -8.01564 100.232 +EDGE_SE3:QUAT 1633 1683 0.0412327 -2.97898 -0.191612 0.0331849 0.00453503 -0.00887973 0.999399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.591 0.0166083 2.44206 399.661 -9.94149 100.339 +EDGE_SE3:QUAT 1634 1684 -0.118428 -3.04648 8.63391e-05 0.0330208 -0.00691681 -0.0177359 0.999273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 -0.020205 -3.10316 399.655 -9.92492 100.324 +EDGE_SE3:QUAT 1635 1685 -0.0262526 -2.97872 -0.0666303 0.0392719 -0.00678216 0.0118598 0.999135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.454 -0.0291313 -3.66599 399.518 -11.7551 100.485 +EDGE_SE3:QUAT 1636 1686 0.00612217 -3.09045 -0.0383116 0.0311763 -0.0047494 0.00384815 0.999495 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.0153746 -2.44476 399.699 -9.34415 100.307 +EDGE_SE3:QUAT 1637 1687 0.061165 -2.83709 -0.02318 0.0370668 -0.00780278 -0.00673358 0.99926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.0277386 -3.74742 399.564 -11.1214 100.448 +EDGE_SE3:QUAT 1638 1688 -0.202789 -3.12508 -0.061688 0.0281816 0.00367543 0.0100782 0.999545 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.00894973 1.66593 399.757 -8.45845 100.236 +EDGE_SE3:QUAT 1639 1689 0.102684 -3.05348 -0.159201 0.0343432 0.00192517 -0.0300338 0.998957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.542 0.0131755 1.5793 399.643 -10.2866 100.269 +EDGE_SE3:QUAT 1640 1690 -0.123522 -3.07836 -0.0645511 0.0248283 0.000245357 0.0392448 0.998921 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 -0.00418362 -0.461771 399.815 -7.45001 100.031 +EDGE_SE3:QUAT 1641 1691 -0.214862 -3.04197 0.0174581 0.0239 -0.00326271 -9.2252e-05 0.999709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 -0.00778334 -1.62925 399.824 -7.16782 100.179 +EDGE_SE3:QUAT 1642 1692 -0.0999051 -3.14174 -0.0649029 0.0395086 0.000278057 0.00319269 0.999214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.376 9.93028e-05 0.0631882 399.532 -11.8435 100.467 +EDGE_SE3:QUAT 1643 1693 -0.0270549 -3.09517 0.0979253 0.0260728 -2.889e-05 -0.00714401 0.999635 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.728 0.00089536 0.097296 399.796 -7.81929 100.199 +EDGE_SE3:QUAT 1644 1694 0.251858 -3.13504 -0.0540823 0.0263647 0.00319795 0.00458775 0.999637 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.00786229 1.52544 399.788 -7.90943 100.213 +EDGE_SE3:QUAT 1645 1695 0.0632309 -3.10388 -0.143395 0.0320829 0.00815367 -0.0166005 0.999314 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 0.0273214 4.39274 399.663 -9.59148 100.333 +EDGE_SE3:QUAT 1646 1696 -0.0132941 -3.06547 0.155902 0.0312995 0.00281436 0.0267578 0.999148 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 0.00372017 0.902816 399.704 -9.40135 100.226 +EDGE_SE3:QUAT 1647 1697 0.15223 -3.0546 0.0286233 0.0278687 -0.000247287 0.0291683 0.999186 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.691 -0.00515023 -0.610933 399.767 -8.35708 100.149 +EDGE_SE3:QUAT 1648 1698 -0.00535924 -2.83381 -0.140466 0.0341365 -0.00895309 0.00348134 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.642 -0.030883 -4.54441 399.618 -10.2267 100.406 +EDGE_SE3:QUAT 1649 1699 0.118396 -3.08906 0.0453904 0.0287299 -0.00108713 0.0320656 0.999072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.677 -0.00815705 -1.09509 399.751 -8.6098 100.148 +EDGE_SE3:QUAT 1650 1700 -0.00102611 -3.14787 -0.167715 0.0242667 -0.0081176 -0.0213475 0.999445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.835 -0.0193831 -3.74493 399.799 -7.31203 100.172 +EDGE_SE3:QUAT 1651 1701 -0.0433758 -2.96061 0.0751878 0.0342959 0.00183829 -0.00506589 0.999397 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 0.0074443 1.02237 399.646 -10.2808 100.353 +EDGE_SE3:QUAT 1652 1702 0.11179 -3.12457 -0.364802 0.0221879 -0.0054571 0.0319866 0.999227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.857 -0.0130259 -3.15094 399.839 -6.6203 100.071 +EDGE_SE3:QUAT 1653 1703 -0.154935 -3.04908 -0.0287741 0.0265537 -0.0105586 0.0038166 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.867 -0.0278761 -5.33882 399.744 -7.953 100.289 +EDGE_SE3:QUAT 1654 1704 0.135974 -3.11749 -0.234774 0.0354004 0.0101235 0.0321198 0.998806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.0323115 4.37056 399.587 -10.6782 100.332 +EDGE_SE3:QUAT 1655 1705 0.0437273 -3.16784 -0.196305 0.0280448 0.00767569 0.0171216 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.749 0.020408 3.54668 399.742 -8.43575 100.244 +EDGE_SE3:QUAT 1656 1706 0.0506714 -3.08938 -0.0608264 0.031366 0.00140607 -0.0103556 0.999453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.611 0.0063809 0.897175 399.704 -9.40235 100.286 +EDGE_SE3:QUAT 1657 1707 0.0812404 -3.04582 -0.0344527 0.0272307 -0.00108919 -0.000248692 0.999629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 -0.00292533 -0.540172 399.777 -8.1662 100.223 +EDGE_SE3:QUAT 1658 1708 0.0544718 -3.13966 -0.0445559 0.03455 -0.00399525 -0.0112053 0.999332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 -0.0113586 -1.76313 399.636 -10.3677 100.355 +EDGE_SE3:QUAT 1659 1709 -0.0549216 -3.11848 0.0220124 0.0271854 -0.00571167 -0.0228364 0.999353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 -0.0131766 -2.48043 399.767 -8.17887 100.188 +EDGE_SE3:QUAT 1660 1710 0.00410954 -2.88244 -0.139973 0.0388502 0.0043248 -0.00800929 0.999204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.426 0.0188684 2.34613 399.539 -11.6388 100.461 +EDGE_SE3:QUAT 1661 1711 -0.208269 -2.79218 -0.0660456 0.0310287 0.00391177 -0.00899637 0.99947 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.0135665 2.12162 399.705 -9.29681 100.293 +EDGE_SE3:QUAT 1662 1712 -0.0558018 -3.05597 -0.129454 0.0373493 0.00421042 0.0361892 0.998638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.448 0.00606174 1.28983 399.576 -11.2297 100.295 +EDGE_SE3:QUAT 1663 1713 0.0266015 -2.95221 -0.206465 0.0243545 0.00472955 0.0114975 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 0.0105528 2.1954 399.814 -7.31487 100.179 +EDGE_SE3:QUAT 1664 1714 -0.0221156 -2.94292 -0.0317615 0.0384077 -0.00229089 -0.0257557 0.998928 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.411 -0.00124229 -0.550129 399.556 -11.5268 100.378 +EDGE_SE3:QUAT 1665 1715 0.0581985 -3.07787 -0.0319369 0.0358334 -0.00519502 0.0494631 0.998119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.026781 -3.6518 399.599 -10.6946 100.173 +EDGE_SE3:QUAT 1666 1716 0.0506571 -3.02512 -0.0852228 0.0214366 -0.00660852 0.00666316 0.999726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.876 -0.0142419 -3.38901 399.844 -6.42001 100.165 +EDGE_SE3:QUAT 1667 1717 0.077404 -3.0042 -0.107131 0.0393392 -0.000503489 0.0161132 0.999096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.383 -0.00691676 -0.631439 399.535 -11.7915 100.439 +EDGE_SE3:QUAT 1668 1718 0.0409891 -3.05918 0.0264745 0.0228087 0.00337989 0.00133177 0.999733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.00759258 1.67099 399.839 -6.84153 100.164 +EDGE_SE3:QUAT 1669 1719 0.108854 -3.03893 -0.0885588 0.0287351 -0.0105808 -0.0122115 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 -0.0307333 -5.07702 399.709 -8.64076 100.307 +EDGE_SE3:QUAT 1670 1720 0.155178 -2.92992 -0.0914363 0.0259526 0.00547985 0.0201655 0.999445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 0.0123671 2.42353 399.787 -7.80531 100.179 +EDGE_SE3:QUAT 1671 1721 0.0784795 -2.79313 -0.310891 0.0249 -0.00809706 -0.0044815 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.834 -0.0201414 -3.98012 399.788 -7.47377 100.229 +EDGE_SE3:QUAT 1672 1722 0.139524 -3.07754 -0.153381 0.0242165 -0.00611176 0.0174007 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.823 -0.0154955 -3.30674 399.808 -7.24115 100.175 +EDGE_SE3:QUAT 1673 1723 -0.130169 -3.03599 -0.273301 0.0260119 0.00353007 0.00253111 0.999652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 0.00888604 1.72453 399.792 -7.8025 100.211 +EDGE_SE3:QUAT 1674 1724 0.0779968 -3.1295 0.00196105 0.042467 0.00250359 0.0603094 0.997273 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.277 -0.011175 -0.288247 399.456 -12.7665 100.179 +EDGE_SE3:QUAT 1675 1725 -0.0435085 -3.10494 -0.320083 0.0420275 0.0120755 0.0328876 0.998502 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.426 0.0456857 5.19527 399.418 -12.6753 100.505 +EDGE_SE3:QUAT 1676 1726 -0.0301303 -2.9805 -0.214438 0.0286134 0.0037279 0.0260695 0.999244 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 0.00677637 1.41412 399.75 -8.60075 100.184 +EDGE_SE3:QUAT 1677 1727 -0.0183632 -3.19129 -0.00449826 0.0287813 -0.00175375 0.00428854 0.999575 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.00572253 -0.950257 399.75 -8.62925 100.249 +EDGE_SE3:QUAT 1678 1728 0.111327 -3.07551 -0.0892905 0.0263724 0.00677604 -0.0144348 0.999525 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 0.0185449 3.61431 399.772 -7.88866 100.223 +EDGE_SE3:QUAT 1679 1729 -0.0589236 -3.02074 0.0763044 0.0378213 0.00142424 -0.0171884 0.999136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.435 0.0101452 1.10087 399.57 -11.3338 100.402 +EDGE_SE3:QUAT 1680 1730 -0.0988038 -3.07371 -0.108336 0.0372977 -0.00793706 -0.0161086 0.999143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.509 -0.0266241 -3.60291 399.559 -11.2061 100.43 +EDGE_SE3:QUAT 1681 1731 -1.00753e-05 -2.92608 -0.106771 0.0370973 -0.00514265 0.0163859 0.999164 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.496 -0.0225646 -2.93244 399.575 -11.1043 100.409 +EDGE_SE3:QUAT 1682 1732 0.0997533 -2.99329 -0.129506 0.0257755 0.0110826 0.0118135 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.882 0.0295325 5.35667 399.753 -7.75416 100.267 +EDGE_SE3:QUAT 1683 1733 -0.0855856 -3.06501 0.0632772 0.0270069 -0.00739846 -0.0269163 0.999245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.761 -0.0181538 -3.25885 399.761 -8.13904 100.179 +EDGE_SE3:QUAT 1684 1734 -0.0372099 -3.0216 -0.239376 0.0275723 -0.0043689 -0.0396991 0.998822 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.706 -0.00669811 -1.52363 399.766 -8.30525 100.079 +EDGE_SE3:QUAT 1685 1735 -0.0751894 -3.03127 -0.0171367 0.0351014 -0.00189742 -0.00889913 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.51 -0.00449101 -0.760254 399.629 -10.5274 100.364 +EDGE_SE3:QUAT 1686 1736 0.0683954 -3.05474 -0.0261658 0.033232 -0.00115752 0.00175493 0.999445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 -0.0042211 -0.613166 399.668 -9.96365 100.332 +EDGE_SE3:QUAT 1687 1737 0.0897784 -2.94217 -0.106125 0.0256618 -0.0039823 0.00671439 0.99964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.0108866 -2.09338 399.796 -7.69038 100.205 +EDGE_SE3:QUAT 1688 1738 -0.0233192 -3.20379 0.0603546 0.0237641 0.00220729 0.0222054 0.999469 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.777 0.00283661 0.786095 399.829 -7.13756 100.122 +EDGE_SE3:QUAT 1689 1739 0.0312816 -3.02489 -0.125454 0.0249609 0.000712348 -0.0171331 0.999541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 0.00386724 0.612401 399.813 -7.48383 100.158 +EDGE_SE3:QUAT 1690 1740 0.050222 -3.08711 -0.260233 0.0268182 -0.000389127 -0.00280432 0.999636 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.000639304 -0.149323 399.784 -8.04281 100.215 +EDGE_SE3:QUAT 1691 1741 0.000232103 -3.12867 -0.0661392 0.0262273 -0.00494014 0.00780603 0.999613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.0136513 -2.59147 399.783 -7.85734 100.219 +EDGE_SE3:QUAT 1692 1742 -0.00234648 -3.00674 -0.064097 0.0357213 -0.00264123 0.0337376 0.998789 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.513 -0.0170702 -2.04042 399.613 -10.6933 100.279 +EDGE_SE3:QUAT 1693 1743 0.0151753 -2.96066 -0.0288111 0.0410537 -0.000393058 0.0129847 0.999072 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.327 -0.00595937 -0.515849 399.494 -12.305 100.489 +EDGE_SE3:QUAT 1694 1744 0.0376473 -3.11896 0.159874 0.0375638 0.00744188 0.0131682 0.99918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 0.0253313 3.4195 399.556 -11.2798 100.44 +EDGE_SE3:QUAT 1695 1745 -0.00373479 -2.95707 -0.035569 0.0277916 -0.00586287 -0.00180201 0.999595 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 -0.0161204 -2.89969 399.755 -8.33568 100.255 +EDGE_SE3:QUAT 1696 1746 -0.144719 -3.07335 0.0154428 0.0321282 -0.0136 0.0145083 0.999286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.85 -0.0417411 -7.07712 399.614 -9.58968 100.426 +EDGE_SE3:QUAT 1697 1747 0.0831829 -2.96305 -0.19567 0.0353161 0.00190593 0.0310403 0.998892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.501 -0.00100213 0.29382 399.625 -10.6017 100.279 +EDGE_SE3:QUAT 1698 1748 0.0399274 -3.04172 -0.0943693 0.0277983 0.00242683 0.00687714 0.999587 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.697 0.00573504 1.09786 399.766 -8.33957 100.231 +EDGE_SE3:QUAT 1699 1749 -0.0447719 -3.14214 -0.068291 0.0214722 -8.78813e-05 -0.0149492 0.999658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.816 0.00118788 0.148638 399.862 -6.44069 100.116 +EDGE_SE3:QUAT 1700 1750 0.0294699 -3.11978 -0.0135458 0.0301921 0.0092856 0.00572901 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 0.0278779 4.53637 399.693 -9.06232 100.329 +EDGE_SE3:QUAT 1701 1751 -0.224595 -3.0665 -0.0867665 0.0319631 -0.00273909 -0.0115536 0.999419 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.598 -0.00649146 -1.14665 399.691 -9.59044 100.297 +EDGE_SE3:QUAT 1702 1752 -0.0987004 -3.09572 -0.168813 0.0304997 -0.00048147 -0.00512247 0.999522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.000514021 -0.146817 399.721 -9.1462 100.277 +EDGE_SE3:QUAT 1703 1753 0.0928793 -3.01206 -0.00747065 0.0327681 0.00306185 0.00468817 0.999447 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.581 0.00907871 1.43732 399.674 -9.82784 100.326 +EDGE_SE3:QUAT 1704 1754 0.136436 -3.29781 -0.010292 0.0353434 0.00253777 -0.00700129 0.999347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 0.0105985 1.41585 399.622 -10.5927 100.375 +EDGE_SE3:QUAT 1705 1755 -0.0985199 -2.9693 0.130487 0.0260683 -0.00659529 0.00396815 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 -0.0174171 -3.35818 399.778 -7.81174 100.234 +EDGE_SE3:QUAT 1706 1756 -0.0243237 -3.13349 -0.0924315 0.0326838 0.0069556 0.0238877 0.999156 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 0.0191995 3.00479 399.662 -9.83315 100.291 +EDGE_SE3:QUAT 1707 1757 0.038385 -3.1399 -0.0395141 0.0276735 -0.000572187 -0.0356659 0.99898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 0.00386622 0.30623 399.77 -8.30471 100.103 +EDGE_SE3:QUAT 1708 1758 -0.0217017 -2.9289 -0.0520931 0.029974 -0.00427334 -0.00386602 0.999534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.012219 -2.06552 399.723 -8.99111 100.28 +EDGE_SE3:QUAT 1709 1759 0.02184 -3.07267 -0.118739 0.0326113 0.00459935 0.0250451 0.999144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.59 0.0102595 1.80645 399.674 -9.80193 100.267 +EDGE_SE3:QUAT 1710 1760 0.0835784 -3.02283 -0.212193 0.0261529 -0.00823846 0.010382 0.99957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.823 -0.0216364 -4.28031 399.767 -7.82481 100.245 +EDGE_SE3:QUAT 1711 1761 0.0616834 -3.16791 -0.119757 0.029659 0.00595486 0.018684 0.999368 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.683 0.0153179 2.642 399.723 -8.91592 100.25 +EDGE_SE3:QUAT 1712 1762 -0.0229592 -2.96465 -0.0271811 0.0266128 -0.00394906 -0.013072 0.999553 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.732 -0.00894625 -1.76437 399.782 -7.99131 100.205 +EDGE_SE3:QUAT 1713 1763 0.0254188 -3.035 -0.087917 0.0309689 2.97675e-05 -0.0389228 0.998762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 0.00743042 0.737502 399.712 -9.28828 100.137 +EDGE_SE3:QUAT 1714 1764 -0.0385847 -3.06702 -0.000142204 0.0383854 0.00360901 -0.0186242 0.999083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.438 0.0186619 2.23041 399.552 -11.4938 100.42 +EDGE_SE3:QUAT 1715 1765 -0.0373318 -2.9153 -0.0751231 0.0337174 -0.00282128 0.0356297 0.998792 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.571 -0.0164983 -2.12799 399.654 -10.091 100.225 +EDGE_SE3:QUAT 1716 1766 0.0665495 -3.08995 -0.0838247 0.0209498 -0.00187897 -0.00428264 0.99977 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 -0.00358194 -0.885286 399.867 -6.28513 100.132 +EDGE_SE3:QUAT 1717 1767 0.115077 -3.11648 -0.0208489 0.0295579 0.00366583 -0.00919989 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.01217 1.99456 399.732 -8.85652 100.264 +EDGE_SE3:QUAT 1718 1768 -0.152788 -3.07458 -0.0430562 0.0294658 0.00549832 -0.00778 0.99952 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.697 0.0170819 2.88472 399.727 -8.82672 100.277 +EDGE_SE3:QUAT 1719 1769 0.0290396 -2.93778 -0.174998 0.0293284 -0.000662401 -0.0257336 0.999238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 0.00248605 0.121859 399.742 -8.79912 100.192 +EDGE_SE3:QUAT 1720 1770 0.0872993 -3.17508 -0.300186 0.0345767 -0.00388001 -0.0066833 0.999372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 -0.0119504 -1.79932 399.636 -10.3717 100.364 +EDGE_SE3:QUAT 1721 1771 -0.0808485 -2.98209 0.0666504 0.0286931 -0.00817161 0.0127971 0.999473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 -0.0238899 -4.30359 399.725 -8.58213 100.281 +EDGE_SE3:QUAT 1722 1772 -0.0741631 -3.10956 -0.357373 0.0217934 0.00842498 0.0133655 0.999638 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.893 0.0186957 4.03615 399.83 -6.5581 100.171 +EDGE_SE3:QUAT 1723 1773 -0.0024191 -3.04392 -0.13162 0.0327628 -0.00138723 0.0171644 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.577 -0.00809487 -1.03004 399.677 -9.81918 100.295 +EDGE_SE3:QUAT 1724 1774 -0.061164 -3.11648 -0.101092 0.0298664 -0.000252286 0.00353346 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 -0.00138137 -0.189341 399.732 -8.95575 100.266 +EDGE_SE3:QUAT 1725 1775 0.0422005 -3.21286 -0.101498 0.0256038 0.000962321 0.0244101 0.999374 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 -0.00073674 0.10578 399.803 -7.68409 100.137 +EDGE_SE3:QUAT 1726 1776 -0.0693445 -2.94606 0.00886117 0.0309792 0.00378392 0.0283498 0.999111 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 0.00666169 1.36233 399.707 -9.31182 100.214 +EDGE_SE3:QUAT 1727 1777 0.0283331 -3.04883 -0.0458735 0.0274231 -0.0120875 -0.0128555 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.874 -0.0344936 -5.82994 399.718 -8.25228 100.306 +EDGE_SE3:QUAT 1728 1778 0.0956368 -3.06028 -0.115547 0.030566 -0.00154987 0.00750043 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 -0.00608614 -0.911765 399.719 -9.1632 100.277 +EDGE_SE3:QUAT 1729 1779 -0.0217363 -2.95882 -0.147397 0.0256586 0.00344686 0.00100911 0.999664 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 0.00872479 1.70695 399.798 -7.69552 100.206 +EDGE_SE3:QUAT 1730 1780 0.0993559 -3.08697 -0.146995 0.0355453 -0.00021716 -0.012016 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.495 0.00226335 0.147706 399.621 -10.6576 100.365 +EDGE_SE3:QUAT 1731 1781 0.269392 -3.16796 -0.106407 0.0307081 -0.000875542 -0.043673 0.998573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.623 0.00552903 0.367258 399.717 -9.21866 100.093 +EDGE_SE3:QUAT 1732 1782 0.0567221 -3.09554 -0.117844 0.0287732 0.0100017 0.0197845 0.99934 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 0.0286655 4.65522 399.714 -8.6666 100.273 +EDGE_SE3:QUAT 1733 1783 -0.0383315 -3.05183 -0.165114 0.0403713 0.00401519 -0.0147347 0.999068 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.378 0.0203939 2.36117 399.504 -12.0895 100.482 +EDGE_SE3:QUAT 1734 1784 0.0273392 -3.22064 -0.0606707 0.0237358 0.00528951 -0.0296828 0.999264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.825 0.0139401 3.0643 399.818 -7.08771 100.105 +EDGE_SE3:QUAT 1735 1785 0.0179814 -3.19759 -0.0163119 0.0381758 0.00482373 -0.0102526 0.999207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.454 0.0208596 2.64348 399.553 -11.4339 100.445 +EDGE_SE3:QUAT 1736 1786 -0.0580247 -3.14452 -0.0615037 0.0252501 -0.0048703 -0.0188039 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 -0.0105295 -2.14831 399.8 -7.59101 100.17 +EDGE_SE3:QUAT 1737 1787 -0.0142271 -2.91858 -0.216564 0.0310651 -0.00440307 0.0348434 0.9989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 -0.0184338 -2.84659 399.7 -9.28549 100.188 +EDGE_SE3:QUAT 1738 1788 0.0322481 -3.35482 -0.0579082 0.0257833 -0.00488189 -0.020678 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.756 -0.0105126 -2.11888 399.792 -7.75279 100.17 +EDGE_SE3:QUAT 1739 1789 -0.107296 -3.17349 -0.00766549 0.0225748 -0.00598957 -0.00932924 0.999684 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.838 -0.013129 -2.86715 399.833 -6.78141 100.168 +EDGE_SE3:QUAT 1740 1790 -0.0283242 -3.10696 -0.151051 0.040433 -0.00988134 0.00255342 0.99913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 -0.0403515 -4.99705 399.47 -12.1119 100.559 +EDGE_SE3:QUAT 1741 1791 0.129306 -3.07778 -0.0748081 0.0340882 0.0161059 -0.00447978 0.999279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.88 0.0542381 8.1436 399.547 -10.1994 100.531 +EDGE_SE3:QUAT 1742 1792 0.0474685 -3.21232 -0.076853 0.0284677 0.00309519 0.0101377 0.999539 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.00729699 1.37325 399.753 -8.5431 100.239 +EDGE_SE3:QUAT 1743 1793 0.0387287 -3.04757 -0.152162 0.0335431 -0.00889657 -0.0239932 0.99911 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.0271998 -3.9596 399.634 -10.0993 100.327 +EDGE_SE3:QUAT 1744 1794 0.109502 -3.01428 -0.0774052 0.0313267 -0.00114503 -0.0103205 0.999455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 -0.00156667 -0.378038 399.705 -9.39592 100.284 +EDGE_SE3:QUAT 1745 1795 -0.00973706 -3.02964 -0.146674 0.0352429 -0.00163845 -0.0246566 0.999073 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.503 0.000343456 -0.296798 399.627 -10.5754 100.313 +EDGE_SE3:QUAT 1746 1796 -0.216773 -2.97528 -0.322252 0.0265739 0.00672268 0.0442495 0.998644 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.75 0.0139253 2.64854 399.773 -8.03093 100.039 +EDGE_SE3:QUAT 1747 1797 0.118012 -3.03699 -0.104414 0.032316 -0.0132651 0.022338 0.99914 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.846 -0.0398381 -7.06148 399.613 -9.62663 100.398 +EDGE_SE3:QUAT 1748 1798 -0.0150702 -3.06263 -0.131972 0.031674 -0.00554658 0.00426257 0.999474 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 -0.0181615 -2.85206 399.686 -9.49197 100.322 +EDGE_SE3:QUAT 1749 1799 0.0492402 -3.07448 -0.168954 0.0374901 -0.0154931 -0.0201327 0.998974 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 -0.0604763 -7.28633 399.487 -11.2961 100.535 +EDGE_SE3:QUAT 1750 1800 0.182859 -3.05399 -0.0975698 0.0286407 -0.000118315 -0.00917715 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.00116624 0.0985471 399.754 -8.58901 100.238 +EDGE_SE3:QUAT 1751 1801 -0.152133 -3.16877 -0.149779 0.0324568 -0.00654029 -0.00239611 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.632 -0.0208908 -3.22084 399.667 -9.73403 100.345 +EDGE_SE3:QUAT 1752 1802 0.125603 -3.09023 -0.0306891 0.0307901 0.00438065 0.0110422 0.999455 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 0.011695 1.98439 399.708 -9.24215 100.284 +EDGE_SE3:QUAT 1753 1803 -0.0365699 -3.04003 -0.15614 0.0346286 0.000215908 -0.00817589 0.999367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.521 0.00270147 0.277632 399.64 -10.3821 100.353 +EDGE_SE3:QUAT 1754 1804 0.0302507 -3.08727 -0.270373 0.0290064 -0.00853259 -0.0170341 0.999398 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.743 -0.0238496 -3.96639 399.72 -8.72636 100.269 +EDGE_SE3:QUAT 1755 1805 0.0189872 -3.05832 -0.242167 0.0312025 -0.00162567 -0.00377253 0.999505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.613 -0.00434393 -0.741513 399.707 -9.35738 100.292 +EDGE_SE3:QUAT 1756 1806 -0.012015 -3.03427 -0.124307 0.035178 -0.00329378 0.00960984 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.523 -0.0137094 -1.84776 399.624 -10.5403 100.371 +EDGE_SE3:QUAT 1757 1807 0.0375861 -3.06606 -0.22404 0.0381497 -0.000620489 0.0166206 0.999134 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.421 -0.00714338 -0.689991 399.563 -11.435 100.41 +EDGE_SE3:QUAT 1758 1808 -0.0955637 -2.97001 0.115194 0.0320758 -0.00825159 -0.0410582 0.998608 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.641 -0.0213866 -3.32659 399.668 -9.68718 100.176 +EDGE_SE3:QUAT 1759 1809 -0.114555 -2.943 -0.0308129 0.0341797 -0.00248437 0.00885613 0.999373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.544 -0.0104161 -1.42238 399.647 -10.2435 100.348 +EDGE_SE3:QUAT 1760 1810 0.0123224 -3.24788 -0.212326 0.0241773 0.00205271 -0.00861123 0.999668 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 0.00588387 1.15066 399.823 -7.24753 100.171 +EDGE_SE3:QUAT 1761 1811 -0.0408912 -3.00739 0.0422893 0.0396758 0.0029116 0.0077934 0.999178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.378 0.00915864 1.26826 399.525 -11.8978 100.471 +EDGE_SE3:QUAT 1762 1812 0.219922 -3.03153 0.0134531 0.0327212 0.00231426 -0.00344662 0.999456 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.58 0.00825892 1.22367 399.677 -9.8094 100.324 +EDGE_SE3:QUAT 1763 1813 -0.0222045 -3.08264 -0.211468 0.0354186 0.00189766 -0.00371078 0.999364 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.504 0.00760812 1.02659 399.622 -10.6174 100.378 +EDGE_SE3:QUAT 1764 1814 0.0415692 -2.96824 -0.000418305 0.0248376 -0.00457827 -0.0295981 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 -0.00846126 -1.84525 399.808 -7.47692 100.109 +EDGE_SE3:QUAT 1765 1815 -0.062842 -3.11635 -0.0526797 0.0296144 -0.00302728 0.00229796 0.999554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.00931587 -1.55331 399.733 -8.87884 100.269 +EDGE_SE3:QUAT 1766 1816 -0.0287574 -3.03978 -0.231726 0.0254498 -0.00639189 0.0220153 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.807 -0.0171843 -3.52941 399.788 -7.60402 100.179 +EDGE_SE3:QUAT 1767 1817 0.0282841 -2.93195 -0.09693 0.0387471 -0.0062137 0.0108036 0.999171 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.459 -0.026424 -3.35393 399.533 -11.6009 100.469 +EDGE_SE3:QUAT 1768 1818 -0.0435599 -2.97465 -0.14503 0.0227122 -0.00543666 0.0411568 0.99888 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.852 -0.0135106 -3.27395 399.831 -6.7683 100.013 +EDGE_SE3:QUAT 1769 1819 0.0680926 -2.90573 -0.211321 0.02599 -0.000899922 -0.00676114 0.999639 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 -0.00142869 -0.344261 399.797 -7.79564 100.198 +EDGE_SE3:QUAT 1770 1820 0.0616235 -3.05767 -0.126215 0.0271725 0.00955278 -0.00873225 0.999547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 0.0257922 4.91693 399.741 -8.13023 100.28 +EDGE_SE3:QUAT 1771 1821 -0.10416 -3.02821 -0.057326 0.0273005 0.00189892 0.0255121 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 0.00143147 0.530566 399.775 -8.19764 100.16 +EDGE_SE3:QUAT 1772 1822 0.192023 -2.87943 -0.114734 0.025567 -0.000756308 -0.0169409 0.999529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 0.000280997 -0.118038 399.804 -7.67051 100.168 +EDGE_SE3:QUAT 1773 1823 -0.178231 -3.0507 -0.0438601 0.0240776 -0.0056805 -0.018477 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.801 -0.0124252 -2.57125 399.814 -7.24211 100.159 +EDGE_SE3:QUAT 1774 1824 -0.0987786 -3.0068 0.0045094 0.0338339 0.00241018 0.0189471 0.999245 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.545 0.00389821 0.819024 399.655 -10.154 100.31 +EDGE_SE3:QUAT 1775 1825 -0.0648302 -2.8894 0.0399057 0.0313828 0.00607557 0.0405278 0.998667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.0126316 2.26823 399.692 -9.46156 100.149 +EDGE_SE3:QUAT 1776 1826 -0.0078235 -3.08813 -0.181108 0.0294526 -0.00729764 -0.00844091 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.716 -0.020779 -3.49719 399.719 -8.84327 100.288 +EDGE_SE3:QUAT 1777 1827 -0.122792 -3.09499 -0.100944 0.028782 -0.00698888 -0.0158008 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 -0.0186882 -3.2187 399.733 -8.65255 100.254 +EDGE_SE3:QUAT 1778 1828 0.0388573 -3.02131 -0.00652277 0.0349605 0.00106903 -0.00375377 0.999381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.513 0.00463559 0.612633 399.633 -10.4809 100.366 +EDGE_SE3:QUAT 1779 1829 -0.000309022 -2.90919 -0.0208505 0.0347887 0.00534624 -0.00811555 0.999347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.559 0.0200739 2.83972 399.625 -10.4209 100.378 +EDGE_SE3:QUAT 1780 1830 -0.108461 -3.1802 -0.18677 0.026381 -0.00110353 0.0191268 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 -0.00547435 -0.853893 399.79 -7.90775 100.174 +EDGE_SE3:QUAT 1781 1831 0.140164 -2.96356 -0.014656 0.0335227 -0.00183799 -0.0083569 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.553 -0.00430576 -0.749993 399.662 -10.0543 100.332 +EDGE_SE3:QUAT 1782 1832 -0.012127 -2.9899 -0.0295551 0.0426825 -0.000572563 -0.00341099 0.999083 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.271 -0.00119428 -0.198509 399.453 -12.7935 100.546 +EDGE_SE3:QUAT 1783 1833 -0.0144925 -3.00285 0.0284105 0.0249581 0.00451782 -0.00722547 0.999652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.78 0.0118822 2.36591 399.805 -7.47822 100.197 +EDGE_SE3:QUAT 1784 1834 0.222172 -3.02502 -0.029758 0.030475 0.00578917 -0.00772089 0.999489 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.677 0.0185607 3.03355 399.707 -9.12858 100.298 +EDGE_SE3:QUAT 1785 1835 -0.0482292 -3.04667 0.0326862 0.0341109 -0.00238455 -0.029431 0.998982 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.535 -0.00135154 -0.588153 399.649 -10.2428 100.264 +EDGE_SE3:QUAT 1786 1836 -0.0335317 -3.04668 -0.0991304 0.0273426 0.000895315 0.000215992 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 0.00241246 0.443815 399.775 -8.19973 100.225 +EDGE_SE3:QUAT 1787 1837 -0.0626125 -3.03427 0.0676801 0.0258046 -0.0015536 -0.0237472 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 -0.000873602 -0.40842 399.8 -7.74688 100.144 +EDGE_SE3:QUAT 1788 1838 0.0471752 -3.08736 0.05968 0.0151515 0.00838912 0.0262393 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.988 0.014508 3.95343 399.904 -4.58875 100.045 +EDGE_SE3:QUAT 1789 1839 0.0188436 -3.06368 0.0720668 0.0409215 0.00566435 -0.00196286 0.999144 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.373 0.0236714 2.8764 399.485 -12.2629 100.525 +EDGE_SE3:QUAT 1790 1840 -0.0206358 -3.06349 -0.261491 0.0340359 0.00688517 0.00463036 0.999386 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 0.0227214 3.34491 399.634 -10.2101 100.377 +EDGE_SE3:QUAT 1791 1841 0.0958677 -3.05315 -0.22173 0.0229663 0.00177365 -0.0234511 0.99946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.797 0.00630714 1.20903 399.84 -6.8803 100.107 +EDGE_SE3:QUAT 1792 1842 -0.0715469 -3.11082 -0.306459 0.0327174 -0.00334044 0.0188234 0.999282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 -0.0143945 -2.03755 399.673 -9.79759 100.296 +EDGE_SE3:QUAT 1793 1843 0.0518907 -2.91562 -0.122442 0.0217207 0.00125583 -0.0434401 0.998819 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 0.00641473 1.1923 399.857 -6.50571 99.9561 +EDGE_SE3:QUAT 1794 1844 -0.0159708 -3.12139 -0.0824815 0.0311613 -0.00146381 -0.0241169 0.999222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.000113366 -0.280205 399.708 -9.3518 100.234 +EDGE_SE3:QUAT 1795 1845 0.120579 -3.15235 0.146184 0.021903 0.00127255 -0.0195793 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.813 0.00455594 0.893028 399.855 -6.56472 100.108 +EDGE_SE3:QUAT 1796 1846 0.123159 -3.01997 -0.253439 0.028867 0.00499107 0.0292862 0.999142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.0103722 1.98485 399.741 -8.68662 100.177 +EDGE_SE3:QUAT 1797 1847 0.144637 -3.16179 -0.265119 0.0382888 -0.00240787 0.0231494 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.43 -0.0155044 -1.73332 399.557 -11.4678 100.393 +EDGE_SE3:QUAT 1798 1848 -0.12162 -2.98479 -0.154439 0.0336037 0.0161784 -0.00196392 0.999302 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.892 0.0543001 8.12806 399.556 -10.0624 100.523 +EDGE_SE3:QUAT 1799 1849 0.132477 -3.03471 -0.145067 0.0304859 0.00554877 -0.00652389 0.999499 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.0177284 2.89161 399.708 -9.13359 100.297 +EDGE_SE3:QUAT 1800 1850 -0.108137 -2.87796 -0.224581 0.0354148 0.000124336 0.00186154 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.498 -2.74195e-05 0.0225587 399.624 -10.6178 100.376 +EDGE_SE3:QUAT 1801 1851 0.042069 -2.80394 -0.18803 0.0310746 -0.00240239 -0.00780578 0.999484 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 -0.00600904 -1.05461 399.708 -9.3216 100.287 +EDGE_SE3:QUAT 1802 1852 -0.0877699 -3.17664 -0.0572846 0.0237236 0.00601072 0.0500675 0.998446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.799 0.0105812 2.28521 399.819 -7.17794 99.9359 +EDGE_SE3:QUAT 1803 1853 -0.0742592 -2.90932 0.0189127 0.0358978 -0.00890444 -0.017905 0.999155 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.567 -0.0295011 -4.06115 399.584 -10.793 100.403 +EDGE_SE3:QUAT 1804 1854 -0.0383705 -3.16786 -0.0654075 0.0292397 0.0103332 -0.00298318 0.999515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.8 0.0302143 5.2169 399.701 -8.75962 100.331 +EDGE_SE3:QUAT 1805 1855 -0.00902558 -2.92915 -0.120399 0.0295278 -0.00290913 -0.0156774 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 -0.00600506 -1.17547 399.736 -8.86383 100.241 +EDGE_SE3:QUAT 1806 1856 -0.0765701 -3.12898 -0.090606 0.038185 0.00740012 0.0372664 0.998548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.454 0.0195931 2.83776 399.544 -11.504 100.326 +EDGE_SE3:QUAT 1807 1857 0.14094 -3.05249 -0.343382 0.0395636 -0.00726182 -0.00701623 0.999166 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.435 -0.027105 -3.45971 399.51 -11.8686 100.499 +EDGE_SE3:QUAT 1808 1858 -0.0761782 -3.09231 -0.0246564 0.0364946 -0.00701899 0.0128364 0.999227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 -0.0277131 -3.78653 399.579 -10.9218 100.422 +EDGE_SE3:QUAT 1809 1859 -0.188033 -2.9272 -0.113857 0.0305127 0.00439332 0.0214612 0.999294 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 0.00990824 1.80124 399.714 -9.16881 100.244 +EDGE_SE3:QUAT 1810 1860 -0.090876 -3.05835 -0.290709 0.0383176 0.00241026 -0.019554 0.999071 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.428 0.0145832 1.65249 399.556 -11.4779 100.409 +EDGE_SE3:QUAT 1811 1861 0.0526861 -3.07877 -0.169244 0.0295712 -0.00521133 -0.0412031 0.998699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.665 -0.00927732 -1.86924 399.729 -8.91265 100.105 +EDGE_SE3:QUAT 1812 1862 0.116739 -2.98034 -0.217091 0.0351536 -0.00269438 0.0100771 0.999327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.519 -0.0117688 -1.55808 399.626 -10.5341 100.367 +EDGE_SE3:QUAT 1813 1863 -0.13546 -3.11522 -0.0917262 0.0346834 -0.00600713 0.00779083 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 -0.022134 -3.16268 399.624 -10.3885 100.382 +EDGE_SE3:QUAT 1814 1864 -0.0866169 -3.00286 -0.293697 0.0364111 0.00128753 0.00178049 0.999334 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.472 0.00420879 0.604118 399.602 -10.9165 100.398 +EDGE_SE3:QUAT 1815 1865 -0.169136 -3.01777 -0.0343924 0.0371005 -0.013417 0.0106035 0.999165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 -0.0492737 -6.94025 399.513 -11.089 100.534 +EDGE_SE3:QUAT 1816 1866 0.10855 -3.03261 -0.123647 0.0295322 0.00317697 -0.00690722 0.999535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.0104308 1.7096 399.734 -8.85123 100.265 +EDGE_SE3:QUAT 1817 1867 0.1199 -3.1384 -0.247879 0.0237117 0.00336077 0.0157604 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.786 0.00643608 1.45503 399.827 -7.12225 100.15 +EDGE_SE3:QUAT 1818 1868 0.101038 -3.15884 -0.0424015 0.0280879 0.00805223 0.0618358 0.997659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 0.0169634 2.96908 399.742 -8.52748 99.8851 +EDGE_SE3:QUAT 1819 1869 0.0952807 -2.85621 0.124586 0.0166181 -0.00516888 -0.000459803 0.999848 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.924 -0.00859029 -2.57945 399.906 -4.9849 100.101 +EDGE_SE3:QUAT 1820 1870 -0.0168166 -3.04721 -0.239359 0.0216045 0.0019555 -0.00781369 0.999734 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.82 0.00488635 1.07857 399.858 -6.47676 100.137 +EDGE_SE3:QUAT 1821 1871 0.0803017 -3.02661 -0.191708 0.0318879 0.00692469 -0.0174021 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 0.0238479 3.79187 399.674 -9.53656 100.313 +EDGE_SE3:QUAT 1822 1872 0.0739379 -2.96847 0.00569321 0.0340952 0.00243786 0.0165514 0.999279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 0.00454421 0.878925 399.649 -10.2311 100.324 +EDGE_SE3:QUAT 1823 1873 -0.0143154 -3.23242 -0.0257429 0.0311035 0.00099062 -0.00690814 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.00439267 0.623738 399.709 -9.32519 100.286 +EDGE_SE3:QUAT 1824 1874 0.0613559 -2.92594 -0.312506 0.0296724 -0.00509829 -0.0260989 0.999206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.0113553 -2.08124 399.727 -8.92501 100.21 +EDGE_SE3:QUAT 1825 1875 0.00772411 -3.10499 -0.0477326 0.033952 -0.000722352 -0.00927524 0.99938 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.539 -0.000311925 -0.171904 399.654 -10.1812 100.337 +EDGE_SE3:QUAT 1826 1876 0.161524 -3.2491 -0.114827 0.0402136 0.000764996 -0.00885675 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.355 0.00590751 0.595495 399.514 -12.0531 100.478 +EDGE_SE3:QUAT 1827 1877 0.186278 -3.11028 -0.0133621 0.0261519 -0.00109636 0.0140601 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 -0.00472915 -0.768309 399.794 -7.84003 100.187 +EDGE_SE3:QUAT 1828 1878 0.0531775 -3.08589 -0.112001 0.0202751 -0.00310903 0.0046503 0.999779 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.849 -0.00659681 -1.61053 399.873 -6.07825 100.128 +EDGE_SE3:QUAT 1829 1879 -0.020543 -3.27013 -0.212735 0.028426 0.00532613 -0.0381677 0.998853 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.737 0.0183942 3.30873 399.744 -8.48482 100.124 +EDGE_SE3:QUAT 1830 1880 -0.00259814 -3.14464 -0.087878 0.0346742 -0.00555511 -0.0221034 0.999139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.545 -0.0147933 -2.31386 399.628 -10.4208 100.329 +EDGE_SE3:QUAT 1831 1881 -0.0893566 -3.07893 -0.18693 0.0305126 0.00104089 0.0220174 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 -0.000925504 0.116887 399.72 -9.15485 100.231 +EDGE_SE3:QUAT 1832 1882 0.116092 -2.92028 -0.0442224 0.0338695 -0.000280326 0.0219717 0.999185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 -0.00593856 -0.586222 399.656 -10.1546 100.297 +EDGE_SE3:QUAT 1833 1883 0.0758564 -3.18104 -0.226805 0.0354614 0.00655375 0.00156118 0.999348 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 0.0229447 3.24043 399.606 -10.6327 100.407 +EDGE_SE3:QUAT 1834 1884 -0.084759 -3.22165 0.0114432 0.0250016 -0.00731362 0.00477852 0.999649 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.823 -0.0184222 -3.72709 399.791 -7.49015 100.224 +EDGE_SE3:QUAT 1835 1885 0.0548894 -2.99025 -0.144123 0.0327005 -0.00300566 -0.0270129 0.999096 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.576 -0.00423046 -0.970713 399.676 -9.82224 100.252 +EDGE_SE3:QUAT 1836 1886 0.0885277 -3.14703 -0.0265822 0.0289181 0.00698944 0.00432766 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 0.0198552 3.41751 399.73 -8.67686 100.282 +EDGE_SE3:QUAT 1837 1887 0.0218338 -3.13588 -0.113553 0.0334584 0.000202103 -0.0496071 0.998208 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.559 0.0114197 1.09543 399.663 -10.0339 100.092 +EDGE_SE3:QUAT 1838 1888 -0.00821434 -3.17133 0.00805733 0.0332218 -0.00472257 -0.0180308 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.578 -0.0122171 -1.9991 399.661 -9.9782 100.311 +EDGE_SE3:QUAT 1839 1889 -0.0509058 -2.91188 -0.212373 0.0337214 -0.0102685 0.000255125 0.999378 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 -0.0346963 -5.13603 399.617 -10.1075 100.415 +EDGE_SE3:QUAT 1840 1890 -0.0505836 -2.91351 -0.250506 0.0415807 -0.00419254 -0.0249177 0.998816 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.318 -0.0091776 -1.47068 399.476 -12.4853 100.465 +EDGE_SE3:QUAT 1841 1891 -0.129239 -3.18183 -0.230686 0.0269165 -0.00124232 -0.041909 0.998758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 0.00273789 0.0564944 399.782 -8.08481 100.042 +EDGE_SE3:QUAT 1842 1892 -0.0535983 -2.92779 -0.0518271 0.0399802 0.00695894 -0.00369072 0.999169 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.427 0.0286304 3.56356 399.501 -11.9779 100.513 +EDGE_SE3:QUAT 1843 1893 0.0324093 -3.19663 -0.0408329 0.0305137 -0.00509062 -0.0239478 0.999234 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.649 -0.0118415 -2.10373 399.712 -9.17469 100.236 +EDGE_SE3:QUAT 1844 1894 -0.0770178 -3.16532 -0.0640183 0.0353209 -0.00525364 -0.0102595 0.99931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.53 -0.0164004 -2.40646 399.615 -10.6 100.381 +EDGE_SE3:QUAT 1845 1895 -0.0234045 -3.15978 -0.0221831 0.0325804 -0.00490328 0.0475841 0.998324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.638 -0.0223424 -3.37414 399.668 -9.72481 100.12 +EDGE_SE3:QUAT 1846 1896 -0.0843723 -3.00494 0.000423335 0.0263941 -0.00639323 -0.0309564 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.0142248 -2.70209 399.777 -7.95574 100.136 +EDGE_SE3:QUAT 1847 1897 0.191385 -2.92016 -0.208971 0.0291492 0.00469765 0.0284522 0.999159 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.0095685 1.84803 399.738 -8.76865 100.185 +EDGE_SE3:QUAT 1848 1898 0.202927 -3.05126 -0.142374 0.0277793 0.00499243 -0.00600824 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 0.0144992 2.59477 399.758 -8.32407 100.246 +EDGE_SE3:QUAT 1849 1899 0.0403644 -3.03129 -0.0179074 0.0307174 -0.00101953 0.014272 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 -0.00576033 -0.772186 399.716 -9.20821 100.264 +EDGE_SE3:QUAT 1850 1900 0.0957077 -3.01279 -0.044987 0.0253151 -0.000578229 -0.00979234 0.999631 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 -0.000208765 -0.140223 399.808 -7.59336 100.183 +EDGE_SE3:QUAT 1851 1901 -0.174056 -3.04715 -0.111642 0.0310714 -0.00356464 0.00689609 0.999487 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 -0.0122126 -1.90932 399.705 -9.31175 100.295 +EDGE_SE3:QUAT 1852 1902 0.0680705 -3.14048 -0.178702 0.0303567 0.00675987 -0.00135227 0.999515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.0206557 3.4023 399.705 -9.09992 100.309 +EDGE_SE3:QUAT 1853 1903 0.00378761 -3.16236 -0.141362 0.0295894 0.00233936 -0.0070948 0.999534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.00806924 1.29466 399.735 -8.86954 100.262 +EDGE_SE3:QUAT 1854 1904 0.095026 -2.88379 -0.278144 0.031069 0.00283162 0.0239108 0.999227 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 0.00433865 0.968354 399.708 -9.33054 100.236 +EDGE_SE3:QUAT 1855 1905 -0.32096 -3.21696 -0.1433 0.0276503 0.00373958 -0.000873244 0.99961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 0.010441 1.88308 399.765 -8.29098 100.239 +EDGE_SE3:QUAT 1856 1906 -0.0141632 -2.94756 -0.266488 0.0363628 0.00109749 -0.00806043 0.999306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.474 0.00608153 0.723843 399.603 -10.8999 100.391 +EDGE_SE3:QUAT 1857 1907 0.123448 -3.11809 -0.0386667 0.0309725 0.00290018 -0.0174037 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 0.0119255 1.77182 399.708 -9.27739 100.265 +EDGE_SE3:QUAT 1858 1908 0.175612 -3.00971 0.0343817 0.0335045 0.000547213 0.0202595 0.999233 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.551 -0.00271617 -0.133832 399.663 -10.0486 100.296 +EDGE_SE3:QUAT 1859 1909 -0.0143492 -3.03281 -0.191016 0.0314676 0.00921089 0.0240635 0.999173 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 0.0272586 4.1457 399.672 -9.47916 100.291 +EDGE_SE3:QUAT 1860 1910 -0.0958643 -3.07388 0.0497909 0.0235628 0.00239025 -0.00638839 0.999699 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 0.0062614 1.28482 399.831 -7.06376 100.167 +EDGE_SE3:QUAT 1861 1911 -0.0332655 -2.95962 0.0264198 0.0288331 -0.00225337 0.00196713 0.99958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.675 -0.00679566 -1.15988 399.749 -8.64533 100.253 +EDGE_SE3:QUAT 1862 1912 -0.0801627 -3.03279 -0.126231 0.0330685 8.98161e-05 0.0127291 0.999372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 -0.00248305 -0.207596 399.672 -9.91562 100.312 +EDGE_SE3:QUAT 1863 1913 -0.0067682 -2.99896 -0.114812 0.032557 -0.00449562 -0.0198026 0.999264 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.593 -0.010923 -1.85829 399.675 -9.78003 100.29 +EDGE_SE3:QUAT 1864 1914 -0.0875273 -3.18437 0.008422 0.0336101 -0.00433115 0.017169 0.999278 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 -0.0176546 -2.50912 399.653 -10.0623 100.326 +EDGE_SE3:QUAT 1865 1915 0.110046 -2.95598 -0.203223 0.0353809 0.0047086 -0.00504042 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.531 0.0176767 2.45877 399.615 -10.6023 100.39 +EDGE_SE3:QUAT 1866 1916 0.165809 -2.92397 -0.0639948 0.0352241 0.00103512 0.00920931 0.999336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.504 0.00136067 0.322395 399.627 -10.5627 100.364 +EDGE_SE3:QUAT 1867 1917 -0.25459 -2.94055 -0.067981 0.0383441 0.00425364 -0.00792617 0.999224 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.44 0.0183053 2.30633 399.551 -11.4875 100.449 +EDGE_SE3:QUAT 1868 1918 0.0744493 -3.18284 -0.0596563 0.0248101 -0.005688 -0.00677919 0.999653 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.0136449 -2.74169 399.803 -7.44794 100.202 +EDGE_SE3:QUAT 1869 1919 0.0474249 -3.14388 -0.120452 0.0261532 0.00038 0.0324886 0.99913 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.00343465 -0.319811 399.795 -7.84711 100.1 +EDGE_SE3:QUAT 1870 1920 -0.131812 -2.99875 -0.0187358 0.0267422 -0.0030923 -0.00845427 0.999602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 -0.00717383 -1.40947 399.782 -8.02496 100.213 +EDGE_SE3:QUAT 1871 1921 0.172469 -3.1663 -0.203053 0.0288579 0.00344379 -0.00171971 0.999576 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.683 0.0101747 1.75045 399.745 -8.65233 100.258 +EDGE_SE3:QUAT 1872 1922 -0.100465 -3.18693 -0.118614 0.0380647 0.000610694 -0.011668 0.999207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.422 0.00567151 0.571258 399.565 -11.4099 100.422 +EDGE_SE3:QUAT 1873 1923 -0.0256783 -3.09551 -0.206493 0.025434 0.0012617 -0.00685318 0.999652 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.00406544 0.735022 399.805 -7.62602 100.191 +EDGE_SE3:QUAT 1874 1924 0.153733 -3.12105 -0.0643246 0.0217604 -0.00386698 -0.00331598 0.99975 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.829 -0.00818278 -1.88945 399.852 -6.52892 100.151 +EDGE_SE3:QUAT 1875 1925 -0.0190031 -3.11941 -0.0322153 0.0268872 0.00120814 0.0443322 0.998654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.0031704 -0.111935 399.783 -8.07661 100.021 +EDGE_SE3:QUAT 1876 1926 0.0236955 -2.959 -0.096646 0.0252526 -0.0135837 0.000558787 0.999589 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.985 -0.034385 -6.80081 399.735 -7.56833 100.321 +EDGE_SE3:QUAT 1877 1927 0.173492 -3.00229 -0.127557 0.029397 0.000559962 0.0304115 0.999105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 -0.00360337 -0.256556 399.74 -8.82006 100.167 +EDGE_SE3:QUAT 1878 1928 -0.162028 -3.22612 -0.195156 0.0359447 -0.000330223 0.0162121 0.999222 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.485 -0.00534341 -0.514345 399.612 -10.7758 100.362 +EDGE_SE3:QUAT 1879 1929 -0.0358555 -3.01209 -0.053434 0.0328632 0.000511504 -0.00983931 0.999411 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 0.00378826 0.449418 399.676 -9.85278 100.315 +EDGE_SE3:QUAT 1880 1930 0.157879 -3.04929 -0.0713773 0.0327452 0.00211421 0.0144674 0.999357 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 0.00387289 0.771767 399.677 -9.82468 100.303 +EDGE_SE3:QUAT 1881 1931 0.0286061 -3.12105 0.0517603 0.0347585 -0.00255893 0.00738906 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.528 -0.010553 -1.43209 399.635 -10.4174 100.362 +EDGE_SE3:QUAT 1882 1932 -0.0399439 -2.92277 -0.0809829 0.0264949 -0.002546 0.035574 0.999013 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 -0.0109126 -1.83601 399.786 -7.92898 100.092 +EDGE_SE3:QUAT 1883 1933 -0.052735 -2.93029 -0.147111 0.0326505 -0.000715079 0.00126988 0.999466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.574 -0.00259913 -0.382066 399.68 -9.78974 100.32 +EDGE_SE3:QUAT 1884 1934 -0.0664556 -2.95549 -0.0643582 0.0368188 -0.00386962 -0.00322471 0.999309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 -0.0134233 -1.86131 399.588 -11.0403 100.416 +EDGE_SE3:QUAT 1885 1935 -0.120315 -3.15726 -0.190176 0.0300004 0.00410467 -0.0128007 0.999459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 0.0141336 2.28089 399.723 -8.98536 100.267 +EDGE_SE3:QUAT 1886 1936 0.154242 -3.04692 -0.0974953 0.0273573 0.000638534 0.0330972 0.999077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.701 -0.00320329 -0.224199 399.775 -8.20984 100.115 +EDGE_SE3:QUAT 1887 1937 -0.0863398 -3.22479 -0.161658 0.0266537 0.00233993 0.0336249 0.999076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 0.00155781 0.630616 399.785 -8.01049 100.102 +EDGE_SE3:QUAT 1888 1938 -0.0734187 -3.02007 0.0673569 0.0339684 0.0057814 -0.0279581 0.999015 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.603 0.0237392 3.45579 399.638 -10.1525 100.299 +EDGE_SE3:QUAT 1889 1939 0.0840464 -3.17894 -0.0339765 0.0261088 -0.00484691 0.0280476 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 -0.0148652 -2.85979 399.785 -7.80318 100.147 +EDGE_SE3:QUAT 1890 1940 0.0570372 -2.8924 -0.0610536 0.0239001 -0.0045212 -0.0179633 0.999543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.791 -0.00927538 -2.00136 399.821 -7.18431 100.151 +EDGE_SE3:QUAT 1891 1941 0.131844 -3.0645 -0.232504 0.0395916 -0.00112963 0.019536 0.999024 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.379 -0.0104418 -1.02762 399.529 -11.8644 100.434 +EDGE_SE3:QUAT 1892 1942 0.0777617 -3.04831 -0.0535451 0.0316617 0.0041232 -0.0187311 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 0.0160264 2.41499 399.691 -9.47833 100.281 +EDGE_SE3:QUAT 1893 1943 -0.128108 -2.88505 -0.155163 0.0295019 0.00275339 -0.0212185 0.999336 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 0.0113529 1.75058 399.735 -8.83543 100.224 +EDGE_SE3:QUAT 1894 1944 0.153072 -3.01143 -0.0797814 0.0338449 -0.00451526 -0.00359012 0.99941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 -0.0145594 -2.18254 399.648 -10.1504 100.356 +EDGE_SE3:QUAT 1895 1945 0.164682 -2.9473 -0.119452 0.030541 -0.000613529 -0.00905616 0.999492 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.627 -0.000183084 -0.14059 399.72 -9.15926 100.272 +EDGE_SE3:QUAT 1896 1946 -0.023264 -3.04771 -0.152045 0.0310459 -0.00256182 0.0197267 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 -0.0113712 -1.64672 399.707 -9.29953 100.257 +EDGE_SE3:QUAT 1897 1947 0.00547007 -3.09013 -0.0511763 0.0310476 0.0111466 -0.00588715 0.999438 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.783 0.0344838 5.68055 399.66 -9.29374 100.375 +EDGE_SE3:QUAT 1898 1948 0.121128 -3.11473 -0.121931 0.0247321 0.00923634 -0.0113964 0.999586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.876 0.0224218 4.78575 399.781 -7.39481 100.233 +EDGE_SE3:QUAT 1899 1949 0.151909 -2.89019 0.101183 0.0296453 -0.00277092 -0.0287576 0.999143 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 -0.00331717 -0.872109 399.734 -8.90676 100.184 +EDGE_SE3:QUAT 1900 1950 -0.0558459 -3.05886 -0.00808693 0.0277814 -0.000926063 -0.00126575 0.999613 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.00237532 -0.441617 399.768 -8.33144 100.232 +EDGE_SE3:QUAT 1901 1951 0.020223 -3.10738 -0.0417297 0.0291807 -0.000793608 -0.00078459 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.66 -0.00217918 -0.382767 399.744 -8.7506 100.256 +EDGE_SE3:QUAT 1902 1952 -0.030244 -3.05845 -0.136567 0.0367789 0.0102381 -0.0239322 0.998984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 0.0388148 5.64074 399.549 -10.9749 100.433 +EDGE_SE3:QUAT 1903 1953 0.0557011 -2.99479 -0.102065 0.033747 -0.00236419 -0.0134808 0.999337 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -0.00497554 -0.907854 399.656 -10.1249 100.326 +EDGE_SE3:QUAT 1904 1954 -0.216131 -3.03897 -0.0433695 0.0342145 0.00689872 -0.0582068 0.997694 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.65 0.0286436 4.63005 399.623 -10.1815 100.065 +EDGE_SE3:QUAT 1905 1955 -0.0897988 -2.97752 -0.10118 0.0201588 0.00536369 0.00654798 0.999761 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.872 0.0106031 2.60181 399.867 -6.05305 100.137 +EDGE_SE3:QUAT 1906 1956 -0.14467 -3.05528 -0.312279 0.0458194 -0.00351307 -0.00349013 0.998937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.174 -0.0146412 -1.65737 399.365 -13.7335 100.637 +EDGE_SE3:QUAT 1907 1957 -0.00123278 -2.90526 -0.26953 0.0314332 -0.00175399 0.0228733 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 -0.00975578 -1.30701 399.702 -9.41795 100.248 +EDGE_SE3:QUAT 1908 1958 -0.0813435 -3.02588 -0.157532 0.0327994 -0.00116362 0.0189713 0.999281 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.00777241 -0.954242 399.676 -9.83061 100.289 +EDGE_SE3:QUAT 1909 1959 -0.0978837 -2.90575 0.093453 0.0305947 -0.0053145 -0.00729991 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 -0.0152149 -2.52114 399.708 -9.18135 100.294 +EDGE_SE3:QUAT 1910 1960 0.0592711 -3.1138 -0.247364 0.0213154 0.00573845 0.0213198 0.999529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.852 0.0113443 2.59451 399.852 -6.41769 100.111 +EDGE_SE3:QUAT 1911 1961 -0.150285 -2.98368 -0.165131 0.0278992 0.00830568 -0.00910494 0.999535 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.786 0.0234125 4.30315 399.738 -8.34996 100.276 +EDGE_SE3:QUAT 1912 1962 -0.0789751 -3.01499 -0.00610366 0.0355287 -0.0123026 -0.0417617 0.99842 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 -0.0417028 -5.24685 399.568 -10.7547 100.29 +EDGE_SE3:QUAT 1913 1963 -0.0355763 -3.07105 -0.0748421 0.0327801 0.00421336 0.0135936 0.999361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 0.0112056 1.83712 399.671 -9.84017 100.314 +EDGE_SE3:QUAT 1914 1964 0.0190411 -2.94673 -0.0715748 0.0304322 0.00391345 -0.00619348 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.652 0.012853 2.06821 399.716 -9.12027 100.286 +EDGE_SE3:QUAT 1915 1965 -0.0626555 -2.99931 -0.241992 0.0326147 -0.00856618 0.00513911 0.999418 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.675 -0.0283469 -4.38062 399.651 -9.76858 100.37 +EDGE_SE3:QUAT 1916 1966 -0.0834555 -3.04717 -0.145403 0.0279801 0.00204184 0.0112385 0.999543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 0.00400335 0.831474 399.764 -8.39544 100.224 +EDGE_SE3:QUAT 1917 1967 -0.0617324 -3.03557 -0.0924446 0.0308769 -0.00238502 0.0118887 0.99945 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 -0.00945202 -1.41155 399.711 -9.25301 100.277 +EDGE_SE3:QUAT 1918 1968 0.108933 -3.15224 -0.290402 0.029947 0.00525335 -0.0014336 0.999537 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 0.0159055 2.65057 399.72 -8.97795 100.288 +EDGE_SE3:QUAT 1919 1969 -0.113101 -3.01724 -0.00961383 0.0334995 0.000836565 -0.0174025 0.999287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.554 0.00663207 0.767374 399.663 -10.0418 100.308 +EDGE_SE3:QUAT 1920 1970 -0.197512 -3.11572 -0.157018 0.0354717 -0.00283702 0.013791 0.999271 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.513 -0.0132288 -1.71012 399.619 -10.627 100.366 +EDGE_SE3:QUAT 1921 1971 -0.179218 -3.18095 -0.0896117 0.0430205 0.00168011 0.0405301 0.99825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.259 -0.00779743 -0.207542 399.444 -12.9113 100.392 +EDGE_SE3:QUAT 1922 1972 -0.0476279 -3.02727 -0.0677929 0.0312145 0.00843307 -0.0237002 0.999196 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 0.0273364 4.65592 399.677 -9.31873 100.294 +EDGE_SE3:QUAT 1923 1973 -0.18019 -3.1274 -0.215239 0.0302608 -0.000997667 -0.0238967 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.633 0.00136095 -0.0645009 399.725 -9.0797 100.218 +EDGE_SE3:QUAT 1924 1974 0.0718273 -3.10457 -0.177574 0.0280845 -2.31898e-07 -0.0267328 0.999248 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.686 0.00418317 0.450126 399.763 -8.42301 100.166 +EDGE_SE3:QUAT 1925 1975 -0.0852625 -2.9934 0.0333761 0.0345677 0.000635934 0.019831 0.999205 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.00254402 -0.0935764 399.641 -10.3673 100.319 +EDGE_SE3:QUAT 1926 1976 -0.0549844 -2.95415 0.0503509 0.0373147 0.00106346 -0.00994587 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.446 0.00668666 0.753587 399.582 -11.1846 100.409 +EDGE_SE3:QUAT 1927 1977 0.0499105 -3.05122 -0.122024 0.0307562 0.00924162 0.00316905 0.999479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 0.0283348 4.55968 399.682 -9.22643 100.341 +EDGE_SE3:QUAT 1928 1978 0.0773659 -3.07539 -0.0405432 0.0262908 8.40043e-05 -0.00514101 0.999641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.724 0.000930508 0.123052 399.793 -7.88446 100.205 +EDGE_SE3:QUAT 1929 1979 0.107398 -3.25687 0.0176977 0.0247408 -0.0109926 0.00393298 0.999626 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.916 -0.0269011 -5.55399 399.768 -7.40906 100.268 +EDGE_SE3:QUAT 1930 1980 -0.11863 -3.04041 -0.122991 0.0244249 0.00572609 -0.00735422 0.999658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.808 0.0144014 2.9695 399.808 -7.3163 100.198 +EDGE_SE3:QUAT 1931 1981 0.0186651 -3.18181 -0.139696 0.027915 0.00484239 -0.00546688 0.999584 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 0.0141146 2.5112 399.757 -8.36546 100.248 +EDGE_SE3:QUAT 1932 1982 -0.0241102 -2.99522 -0.167005 0.0376208 -0.00910626 -0.00466268 0.99924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.536 -0.0336086 -4.44323 399.543 -11.2845 100.478 +EDGE_SE3:QUAT 1933 1983 0.135014 -2.82967 -0.252255 0.0320792 0.00495244 0.0262864 0.999127 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 0.011213 1.9668 399.683 -9.64556 100.252 +EDGE_SE3:QUAT 1934 1984 0.044808 -3.12939 -0.0859541 0.0426718 -0.00671841 -0.0347902 0.998461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.298 -0.0175165 -2.4603 399.439 -12.8384 100.447 +EDGE_SE3:QUAT 1935 1985 0.0236924 -3.08302 -0.0928126 0.0336214 -0.00177227 -0.0267004 0.999076 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 6.17565e-05 -0.346372 399.66 -10.0914 100.269 +EDGE_SE3:QUAT 1936 1986 -0.00505125 -3.11936 -0.122213 0.0345862 -0.00220229 0.0287918 0.998984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 -0.0139249 -1.69631 399.638 -10.3581 100.283 +EDGE_SE3:QUAT 1937 1987 0.0263322 -2.97505 -0.133867 0.0238883 -0.00502399 0.00923781 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 -0.0125938 -2.64316 399.818 -7.15476 100.182 +EDGE_SE3:QUAT 1938 1988 0.0091196 -3.11688 -0.178431 0.0230462 0.00293696 0.00117845 0.999729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.798 0.00665628 1.45152 399.837 -6.91256 100.165 +EDGE_SE3:QUAT 1939 1989 -0.00433661 -3.26607 0.0314002 0.0224755 0.00359991 -0.0068688 0.999717 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.817 0.00860543 1.89177 399.843 -6.7358 100.157 +EDGE_SE3:QUAT 1940 1990 -0.0190984 -3.22341 -0.0442282 0.0284394 0.00693926 -0.0127295 0.99949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.748 0.0205706 3.68448 399.737 -8.50979 100.263 +EDGE_SE3:QUAT 1941 1991 0.0897336 -2.94896 -0.0238168 0.0167436 0.00203934 -0.0363956 0.999195 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.898 0.00497356 1.38368 399.914 -5.00852 99.9563 +EDGE_SE3:QUAT 1942 1992 -0.107628 -3.15056 0.040788 0.0175071 0.00122295 0.0113693 0.999781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.879 0.00146343 0.49183 399.908 -5.25419 100.08 +EDGE_SE3:QUAT 1943 1993 0.0377913 -2.97537 -0.00858782 0.0236569 0.000576172 -0.00381998 0.999713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.777 0.00178585 0.342148 399.832 -7.09464 100.167 +EDGE_SE3:QUAT 1944 1994 -0.200275 -3.02643 -0.145734 0.0273898 0.00739404 0.0414631 0.998737 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.743 0.016814 3.00823 399.756 -8.2768 100.082 +EDGE_SE3:QUAT 1945 1995 0.0516165 -2.97591 -0.0560244 0.0375466 -0.00381848 -0.0209231 0.999069 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.445 -0.00872916 -1.43502 399.572 -11.2726 100.386 +EDGE_SE3:QUAT 1946 1996 0.121357 -3.04053 -0.200719 0.0306035 -0.00113012 0.0288313 0.999115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.632 -0.00862318 -1.09328 399.718 -9.17141 100.201 +EDGE_SE3:QUAT 1947 1997 -0.0308405 -3.04748 0.0571645 0.0262488 -0.001789 0.0410187 0.998812 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 -0.00969201 -1.53817 399.791 -7.85926 100.044 +EDGE_SE3:QUAT 1948 1998 0.0536134 -3.12658 -0.320196 0.0342898 0.00556119 0.0190858 0.999214 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 0.0153531 2.38442 399.636 -10.3021 100.334 +EDGE_SE3:QUAT 1949 1999 0.030286 -3.07141 -0.0710082 0.0330307 -0.00716809 -0.016034 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.617 -0.02141 -3.26249 399.654 -9.92613 100.333 +EDGE_SE3:QUAT 1950 2000 0.0148607 -3.13423 -0.138566 0.0316894 -0.000870875 0.00506251 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.0037606 -0.53126 399.698 -9.50117 100.299 +EDGE_SE3:QUAT 1951 2001 0.0521878 -3.03471 0.0377428 0.0299067 -0.00256136 0.0329582 0.999006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 -0.0127576 -1.86953 399.728 -8.95242 100.168 +EDGE_SE3:QUAT 1952 2002 0.0312852 -3.05352 -0.188157 0.0339545 0.00939465 -0.0220612 0.999136 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 0.0329034 5.14168 399.616 -10.1372 100.368 +EDGE_SE3:QUAT 1953 2003 -0.138849 -3.01898 -0.0750788 0.0306246 -0.00418045 0.0113736 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.653 -0.0144956 -2.29732 399.711 -9.17328 100.282 +EDGE_SE3:QUAT 1954 2004 -0.00099052 -3.14651 -0.0146388 0.0384426 -0.00794139 -0.00182173 0.999228 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.489 -0.0301737 -3.92424 399.532 -11.5254 100.486 +EDGE_SE3:QUAT 1955 2005 0.0925024 -3.09935 -0.0978751 0.0405186 -0.00255619 0.0231459 0.998907 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.362 -0.0173886 -1.838 399.504 -12.1344 100.447 +EDGE_SE3:QUAT 1956 2006 -0.194563 -3.01287 0.0205387 0.0300011 0.00268839 0.0152112 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.645 0.00544473 1.06913 399.728 -9.00469 100.251 +EDGE_SE3:QUAT 1957 2007 0.105266 -2.96184 -0.111297 0.0289315 -0.00375662 0.0326667 0.99904 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.698 -0.0149771 -2.44204 399.742 -8.65231 100.159 +EDGE_SE3:QUAT 1958 2008 -0.108838 -2.9883 -0.0176286 0.0331256 0.00511183 -0.011091 0.999377 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 0.0187428 2.77378 399.66 -9.92036 100.338 +EDGE_SE3:QUAT 1959 2009 0.0198086 -2.87677 -0.0693471 0.0232744 0.00433031 -0.0311227 0.999235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.82 0.0119782 2.5969 399.829 -6.95414 100.083 +EDGE_SE3:QUAT 1960 2010 0.0620823 -2.86315 -0.146143 0.0258317 -0.00274785 0.00839878 0.999627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 -0.00807695 -1.50321 399.797 -7.74224 100.199 +EDGE_SE3:QUAT 1961 2011 -0.104128 -3.09505 -0.0121927 0.0331463 0.00132345 0.0104326 0.999395 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.00210241 0.453607 399.67 -9.94135 100.319 +EDGE_SE3:QUAT 1962 2012 -0.0382338 -3.00643 -0.0654127 0.0282802 -0.00542095 -0.0255118 0.99926 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 -0.0122132 -2.27438 399.75 -8.5088 100.191 +EDGE_SE3:QUAT 1963 2013 -0.103737 -3.12396 -0.270104 0.0308312 -0.00704486 0.0395968 0.998715 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.0242647 -4.24759 399.691 -9.18994 100.174 +EDGE_SE3:QUAT 1964 2014 -0.0410864 -3.12942 -0.121939 0.0336835 -0.00905018 0.0119884 0.99932 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 -0.0312995 -4.76367 399.625 -10.0756 100.388 +EDGE_SE3:QUAT 1965 2015 -0.00394692 -3.12284 -0.120259 0.0233405 -0.00263266 -0.0405846 0.9989 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.784 -0.00189464 -0.745787 399.834 -7.0235 100.001 +EDGE_SE3:QUAT 1966 2016 0.035538 -3.01311 -0.167803 0.0370063 -0.00843189 0.0256608 0.99895 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 -0.0341171 -4.77936 399.557 -11.0498 100.405 +EDGE_SE3:QUAT 1967 2017 0.00160172 -3.00319 -0.289741 0.0190242 0.00489198 0.00727938 0.999781 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.884 0.00907468 2.36217 399.882 -5.71307 100.119 +EDGE_SE3:QUAT 1968 2018 0.0183999 -2.92201 0.0329823 0.0281005 -0.00187795 0.0295278 0.999167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 -0.00951915 -1.4352 399.761 -8.41677 100.155 +EDGE_SE3:QUAT 1969 2019 0.0269479 -3.06412 -0.134239 0.0206236 0.00265844 -0.0243356 0.999488 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.844 0.00709857 1.6291 399.869 -6.17326 100.075 +EDGE_SE3:QUAT 1970 2020 -0.000304255 -3.18856 -0.112986 0.0312928 0.00454786 0.019164 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 0.0109768 1.91159 399.699 -9.40088 100.269 +EDGE_SE3:QUAT 1971 2021 0.0243198 -2.98738 -0.23178 0.0397294 -0.000648853 0.0337096 0.998641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.376 -0.0129352 -1.1265 399.525 -11.9071 100.363 +EDGE_SE3:QUAT 1972 2022 0.0411305 -2.97061 -0.0454571 0.0401436 -0.00146666 -0.00543556 0.999178 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.357 -0.00413309 -0.601398 399.516 -12.035 100.482 +EDGE_SE3:QUAT 1973 2023 0.110846 -3.00954 -0.0460256 0.0260194 -0.0041916 -0.0357799 0.999012 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 -0.00668722 -1.53392 399.791 -7.83467 100.083 +EDGE_SE3:QUAT 1974 2024 -0.0597523 -3.03427 -0.0776605 0.0207607 0.00121989 0.0298401 0.999338 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.828 -2.75791e-05 0.237684 399.87 -6.23506 100.041 +EDGE_SE3:QUAT 1975 2025 -0.0932133 -3.05779 -0.152591 0.0287129 -0.00197167 0.0199033 0.999388 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.008692 -1.32754 399.751 -8.60289 100.212 +EDGE_SE3:QUAT 1976 2026 0.00357393 -3.23914 -0.161052 0.0343744 -0.00232047 0.026525 0.999054 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.544 -0.0137004 -1.70508 399.642 -10.2948 100.291 +EDGE_SE3:QUAT 1977 2027 -0.180899 -3.16128 -0.147999 0.0423354 0.001713 0.0110517 0.999041 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.284 0.00329621 0.574477 399.461 -12.6932 100.527 +EDGE_SE3:QUAT 1978 2028 -0.13379 -3.24197 -0.172663 0.0277475 -0.00319952 -0.0229474 0.999346 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 -0.00558833 -1.21603 399.766 -8.33632 100.183 +EDGE_SE3:QUAT 1979 2029 0.157572 -3.08483 -0.015791 0.0280957 0.00212405 -0.000771586 0.999603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 0.00607465 1.07429 399.761 -8.42495 100.24 +EDGE_SE3:QUAT 1980 2030 0.0558258 -3.01001 -0.158652 0.0353861 -0.0176043 0.00838192 0.999183 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.92 -0.0601615 -8.97989 399.499 -10.5714 100.592 +EDGE_SE3:QUAT 1981 2031 0.0523394 -3.16742 -0.19736 0.0239876 0.00362482 0.002455 0.999703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.786 0.00846265 1.77621 399.822 -7.19576 100.181 +EDGE_SE3:QUAT 1982 2032 -0.21673 -2.86464 -0.162463 0.0313962 0.00299352 -0.00163822 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.618 0.00967874 1.52633 399.701 -9.41301 100.302 +EDGE_SE3:QUAT 1983 2033 -0.144195 -3.13249 0.00132992 0.0351445 -0.00156696 0.000758216 0.999381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.509 -0.00567763 -0.798596 399.628 -10.5365 100.372 +EDGE_SE3:QUAT 1984 2034 -0.0670177 -2.888 0.237676 0.0283502 -0.00542583 0.0357465 0.998944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.738 -0.0183814 -3.31607 399.745 -8.46373 100.141 +EDGE_SE3:QUAT 1985 2035 -0.0209647 -3.17551 -0.267033 0.0267478 0.00564813 0.0154867 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.747 0.0136336 2.57338 399.774 -8.03875 100.21 +EDGE_SE3:QUAT 1986 2036 -0.0238239 -2.8232 -0.0525839 0.035484 -0.00334775 0.0235765 0.999086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.0170205 -2.17297 399.616 -10.6232 100.334 +EDGE_SE3:QUAT 1987 2037 -0.0504269 -3.11407 -0.185938 0.026273 -0.00309676 -0.0129158 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.733 -0.00651594 -1.34367 399.789 -7.88726 100.196 +EDGE_SE3:QUAT 1988 2038 -0.0189585 -3.07027 -0.0683004 0.0373403 -0.00496934 -0.0113267 0.999226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 -0.0157719 -2.22776 399.573 -11.2052 100.42 +EDGE_SE3:QUAT 1989 2039 0.0147197 -3.09238 -0.208605 0.028437 0.00174122 0.0162604 0.999462 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.678 0.00235848 0.59243 399.756 -8.53366 100.217 +EDGE_SE3:QUAT 1990 2040 0.032072 -3.24973 -0.0696703 0.0338669 0.00727433 0.0142937 0.999298 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.598 0.0225062 3.34289 399.636 -10.1742 100.357 +EDGE_SE3:QUAT 1991 2041 -0.0359589 -3.21296 -0.0623838 0.0371676 0.0124303 -0.00672145 0.999209 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.659 0.0462669 6.36068 399.523 -11.1215 100.522 +EDGE_SE3:QUAT 1992 2042 -0.0774013 -3.063 -0.0814995 0.0386764 0.00142933 0.0156679 0.999128 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.402 0.000843088 0.350168 399.551 -11.5992 100.425 +EDGE_SE3:QUAT 1993 2043 -0.0160024 -2.94983 0.0273565 0.0342738 -0.00843061 0.0123674 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 -0.0300618 -4.46581 399.618 -10.2535 100.391 +EDGE_SE3:QUAT 1994 2044 0.0384637 -3.16603 -0.0156016 0.0320163 -0.00821522 0.021847 0.999215 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 -0.0276402 -4.52295 399.663 -9.56293 100.314 +EDGE_SE3:QUAT 1995 2045 0.010927 -3.03111 0.0104183 0.0273036 0.000599073 0.00556784 0.999612 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.702 0.000805251 0.208138 399.776 -8.18873 100.221 +EDGE_SE3:QUAT 1996 2046 0.097244 -2.99099 0.048626 0.0250099 0.000232007 0.0106545 0.99963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.75 -0.000752945 -0.0439152 399.812 -7.50127 100.176 +EDGE_SE3:QUAT 1997 2047 -0.0624482 -3.01433 -0.0802096 0.0359118 0.000301743 -0.00497409 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.485 0.00236076 0.257823 399.613 -10.7663 100.385 +EDGE_SE3:QUAT 1998 2048 -0.00224381 -3.00439 0.0464199 0.0249128 -0.00596392 -6.45424e-05 0.999672 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.798 -0.0148555 -2.9797 399.8 -7.47094 100.211 +EDGE_SE3:QUAT 1999 2049 -0.0144345 -3.06316 -0.175608 0.0256994 -0.0015485 -0.00182007 0.999667 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.0037416 -0.745734 399.801 -7.70778 100.199 +EDGE_SE3:QUAT 2000 2050 -0.0643962 -3.18008 -0.166869 0.0276149 0.00304041 -0.029299 0.999185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.717 0.0120421 2.00332 399.766 -8.26436 100.153 +EDGE_SE3:QUAT 2001 2051 0.0371151 -3.14533 -0.0838149 0.0325699 0.000634199 -0.0146776 0.999361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.578 0.00513832 0.603448 399.681 -9.76425 100.298 +EDGE_SE3:QUAT 2002 2052 0.0835603 -3.07361 -0.0633718 0.0264114 -0.000938451 -0.0210182 0.99943 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 0.000453044 -0.135799 399.79 -7.92517 100.165 +EDGE_SE3:QUAT 2003 2053 0.115243 -3.09724 -0.138628 0.0336437 -0.000891994 -0.000160628 0.999433 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.548 -0.00295818 -0.442303 399.66 -10.0874 100.34 +EDGE_SE3:QUAT 2004 2054 -0.0706894 -3.09164 0.00896299 0.0303249 0.0106144 0.0091939 0.999441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.768 0.0323198 5.13702 399.68 -9.1105 100.343 +EDGE_SE3:QUAT 2005 2055 -0.0874422 -3.10329 -0.0692837 0.02906 -0.0065451 -0.00731891 0.999529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 -0.0183036 -3.14274 399.73 -8.7231 100.276 +EDGE_SE3:QUAT 2006 2056 -0.0634775 -2.90446 0.0393535 0.0466519 -0.000180602 0.0287762 0.998497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.134 -0.0132135 -0.894746 399.346 -13.9811 100.572 +EDGE_SE3:QUAT 2007 2057 -0.00118421 -3.20395 -0.0703197 0.0265975 0.00885746 0.0152625 0.99949 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.0233652 4.18244 399.758 -8.00235 100.24 +EDGE_SE3:QUAT 2008 2058 0.089576 -3.17679 -0.0790087 0.0205307 -0.000194228 -0.00571589 0.999773 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.831 8.32984e-05 -0.0266742 399.874 -6.15816 100.123 +EDGE_SE3:QUAT 2009 2059 0.154141 -3.27799 -0.190217 0.0348234 0.000128234 -0.00296872 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.515 0.00116474 0.12605 399.636 -10.4406 100.363 +EDGE_SE3:QUAT 2010 2060 0.0586031 -3.08102 -0.193086 0.0286831 -0.00213087 0.00180515 0.999585 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.677 -0.00638442 -1.09572 399.751 -8.60051 100.25 +EDGE_SE3:QUAT 2011 2061 -0.0205971 -2.98712 -0.255829 0.0332525 -0.00692338 -0.0151062 0.999309 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.608 -0.0207635 -3.15666 399.65 -9.99051 100.338 +EDGE_SE3:QUAT 2012 2062 0.0452902 -2.97497 -0.245561 0.0252062 0.00119601 0.00676239 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.747 0.00216421 0.495389 399.809 -7.56111 100.187 +EDGE_SE3:QUAT 2013 2063 -0.00247814 -3.00499 -0.19276 0.0335352 0.00181446 0.0083156 0.999401 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.553 0.00423601 0.739009 399.661 -10.058 100.332 +EDGE_SE3:QUAT 2014 2064 0.123495 -3.09005 -0.223313 0.0345297 0.00317932 0.0101737 0.999347 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 0.00867213 1.37715 399.639 -10.3592 100.353 +EDGE_SE3:QUAT 2015 2065 -0.00684393 -3.1065 0.0218204 0.0269209 -0.00103057 0.0402411 0.998827 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.718 -0.00824717 -1.16372 399.781 -8.06711 100.058 +EDGE_SE3:QUAT 2016 2066 0.00874849 -2.94551 -0.0028244 0.0299072 -0.011332 -0.0200249 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 -0.0344801 -5.30211 399.683 -9.01151 100.31 +EDGE_SE3:QUAT 2017 2067 0.0724536 -3.15653 -0.241265 0.0386307 -9.79413e-05 -0.00670887 0.999231 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.403 0.00162327 0.106519 399.552 -11.5808 100.443 +EDGE_SE3:QUAT 2018 2068 -0.146806 -3.01057 -0.121051 0.0258123 0.00614799 -0.00323669 0.999643 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.784 0.0160765 3.12267 399.785 -7.73639 100.226 +EDGE_SE3:QUAT 2019 2069 -0.0806291 -2.9969 -0.0175986 0.0274486 -0.00445002 0.0175799 0.999459 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.732 -0.0140722 -2.51256 399.765 -8.21576 100.212 +EDGE_SE3:QUAT 2020 2070 0.186252 -3.24149 -0.179033 0.0354589 0.00399858 0.0297977 0.998919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.505 0.00707933 1.36194 399.618 -10.6562 100.295 +EDGE_SE3:QUAT 2021 2071 -0.0481338 -3.13361 -0.101039 0.0299918 -0.00857968 -0.010016 0.999463 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.0251724 -4.10671 399.702 -9.00927 100.308 +EDGE_SE3:QUAT 2022 2072 0.112971 -3.1146 -0.0905336 0.0258638 0.000454822 -0.00367071 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.733 0.00166365 0.284222 399.799 -7.75624 100.2 +EDGE_SE3:QUAT 2023 2073 0.0200438 -3.02608 -0.0331133 0.0173034 0.00357312 0.0373764 0.999145 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.889 0.00448721 1.39603 399.906 -5.21809 99.9566 +EDGE_SE3:QUAT 2024 2074 -0.0596035 -3.19203 0.00444458 0.0293302 0.00262934 -0.00131668 0.999565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.665 0.0079103 1.33685 399.739 -8.79442 100.263 +EDGE_SE3:QUAT 2025 2075 -0.154515 -3.15247 -0.0985383 0.0323403 0.00233786 -0.00561762 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.59 0.00865629 1.27679 399.684 -9.69429 100.315 +EDGE_SE3:QUAT 2026 2076 0.00105436 -3.13418 -0.189395 0.0320865 -0.00277165 0.0281804 0.999084 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 -0.0139621 -1.92588 399.687 -9.6063 100.238 +EDGE_SE3:QUAT 2027 2077 0.11636 -3.03798 -0.0808031 0.0360672 -0.000624583 0.00440606 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.481 -0.00338741 -0.407228 399.61 -10.8126 100.389 +EDGE_SE3:QUAT 2028 2078 -0.0823317 -2.97797 -0.0764544 0.0343894 -0.0085752 -0.0253166 0.999051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 -0.0261198 -3.75912 399.619 -10.3537 100.334 +EDGE_SE3:QUAT 2029 2079 -0.083409 -3.16984 -0.117541 0.0298267 -0.00217069 -0.015614 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.647 -0.00376276 -0.804919 399.732 -8.9511 100.245 +EDGE_SE3:QUAT 2030 2080 -0.026439 -3.08984 -0.168958 0.0334044 0.00248474 0.00291384 0.999435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 0.00766294 1.18275 399.663 -10.0171 100.338 +EDGE_SE3:QUAT 2031 2081 -0.0878578 -3.23564 -0.0802511 0.0276929 0.00300872 0.0078252 0.999581 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 0.00722943 1.37329 399.767 -8.30932 100.23 +EDGE_SE3:QUAT 2032 2082 0.16457 -3.02033 -0.00474537 0.0272694 0.00111396 -0.0193825 0.99944 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 0.00581508 0.873444 399.776 -8.17391 100.187 +EDGE_SE3:QUAT 2033 2083 0.096681 -3.17533 -0.179596 0.0263908 -0.00356436 -0.00562291 0.99963 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.736 -0.0087313 -1.69206 399.786 -7.91831 100.214 +EDGE_SE3:QUAT 2034 2084 -0.0175213 -3.17233 -0.355849 0.029872 -0.000518488 0.0102543 0.999501 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.644 -0.00336188 -0.442741 399.732 -8.95667 100.258 +EDGE_SE3:QUAT 2035 2085 -0.00208623 -3.05323 -0.113959 0.0414061 0.00428545 0.0119695 0.999062 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.331 0.0138901 1.84203 399.479 -12.4213 100.51 +EDGE_SE3:QUAT 2036 2086 -0.201835 -2.89584 -0.104823 0.0250334 -0.00694674 -0.0172209 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 -0.0165307 -3.21232 399.794 -7.53117 100.189 +EDGE_SE3:QUAT 2037 2087 -0.0342074 -3.03427 -0.0389665 0.0359777 -0.00237535 0.0102854 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.0110444 -1.40815 399.609 -10.7814 100.383 +EDGE_SE3:QUAT 2038 2088 -0.0874539 -3.00212 -0.127525 0.0276823 0.00219784 0.00097527 0.999614 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.7 0.0059347 1.08198 399.768 -8.30185 100.233 +EDGE_SE3:QUAT 2039 2089 -0.105224 -2.97762 -0.249731 0.0450843 -0.00629275 -0.00259976 0.99896 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.236 -0.0274164 -3.07071 399.375 -13.5136 100.636 +EDGE_SE3:QUAT 2040 2090 0.0733136 -2.91418 -0.0160392 0.0307474 0.001441 0.0226172 0.99927 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.622 0.000164674 0.302506 399.716 -9.22715 100.233 +EDGE_SE3:QUAT 2041 2091 0.00508262 -2.97265 -0.0364925 0.0306225 -1.46907e-05 -0.00453868 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.625 0.000805767 0.0760257 399.719 -9.18247 100.279 +EDGE_SE3:QUAT 2042 2092 0.0856552 -2.91678 -0.286219 0.0211913 0.00435288 0.0179159 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.839 0.00810956 1.94728 399.858 -6.37167 100.114 +EDGE_SE3:QUAT 2043 2093 0.173001 -3.01187 -0.172236 0.0349672 -0.0175246 -0.0091012 0.999193 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.889 -0.0644019 -8.56967 399.513 -10.5079 100.567 +EDGE_SE3:QUAT 2044 2094 -0.170521 -3.00903 0.0820987 0.0328047 0.00242545 0.00749079 0.999431 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.575 0.00639162 1.06412 399.675 -9.83971 100.321 +EDGE_SE3:QUAT 2045 2095 -0.0344129 -3.17738 -0.210418 0.0375241 -0.002459 0.00180362 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.445 -0.00969025 -1.26856 399.575 -11.2482 100.427 +EDGE_SE3:QUAT 2046 2096 0.0357437 -2.97089 -0.172259 0.0188334 0.00541304 0.0282247 0.99941 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.886 0.00937169 2.38506 399.883 -5.68 100.044 +EDGE_SE3:QUAT 2047 2097 -0.179329 -3.05595 -0.199372 0.0278514 -0.000265231 -0.00456042 0.999602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 -3.04484e-05 -0.0563323 399.767 -8.35246 100.231 +EDGE_SE3:QUAT 2048 2098 0.0239904 -3.14064 -0.0721547 0.0314098 0.00176654 -0.000700635 0.999505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 0.00567256 0.895697 399.703 -9.41798 100.298 +EDGE_SE3:QUAT 2049 2099 0.0447434 -3.06865 -0.206976 0.0206849 0.000916442 0.0176768 0.999629 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.829 0.000389683 0.238584 399.871 -6.2077 100.097 +EDGE_SE3:QUAT 2050 2100 -0.123194 -2.78671 -0.255897 0.0389303 0.000437474 0.00308148 0.999237 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.394 0.000765118 0.146496 399.545 -11.6705 100.454 +EDGE_SE3:QUAT 2051 2101 0.0189238 -3.13952 -0.119553 0.0287856 -0.0100833 -0.00140575 0.999534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.799 -0.0291097 -5.01538 399.711 -8.63275 100.319 +EDGE_SE3:QUAT 2052 2102 -0.154336 -3.15101 0.00879614 0.0367386 0.0097053 -0.00111326 0.999277 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.584 0.0357989 4.8729 399.557 -11.0094 100.471 +EDGE_SE3:QUAT 2053 2103 0.0214168 -3.01003 0.0169212 0.0295538 0.00517065 -0.0118522 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 0.0166849 2.79339 399.727 -8.84955 100.269 +EDGE_SE3:QUAT 2054 2104 0.0983086 -3.02869 -0.0370127 0.0351506 0.00418628 0.00830648 0.999339 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.524 0.0128574 1.91566 399.623 -10.5453 100.375 +EDGE_SE3:QUAT 2055 2105 0.185214 -3.3471 0.0350969 0.0309714 -0.00142709 0.00755842 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 -0.00582271 -0.853314 399.711 -9.28481 100.284 +EDGE_SE3:QUAT 2056 2106 -0.0120497 -3.04035 -0.225792 0.0276647 -0.00732157 -0.0362904 0.998931 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 -0.0171982 -3.05226 399.752 -8.35044 100.127 +EDGE_SE3:QUAT 2057 2107 -0.149921 -2.95745 -0.165196 0.0369436 0.00585777 0.0325001 0.998772 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 0.0139148 2.20276 399.579 -11.115 100.32 +EDGE_SE3:QUAT 2058 2108 0.000495389 -2.98658 -0.0119766 0.0269644 -0.00183259 0.00586438 0.999618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 -0.00574507 -1.01053 399.78 -8.08421 100.217 +EDGE_SE3:QUAT 2059 2109 -0.0916159 -2.94045 -0.216918 0.0347193 0.00310211 -0.0150439 0.999279 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 0.0140096 1.8624 399.634 -10.4002 100.348 +EDGE_SE3:QUAT 2060 2110 -0.0533854 -2.85278 0.00704746 0.0305783 0.00125349 0.0327306 0.998996 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.626 -0.00229506 0.0255063 399.719 -9.17905 100.174 +EDGE_SE3:QUAT 2061 2111 -0.146266 -3.00686 -0.215619 0.0221934 -0.0107164 -0.0106009 0.99964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.943 -0.0248968 -5.21607 399.807 -6.67737 100.214 +EDGE_SE3:QUAT 2062 2112 -0.129272 -3.03663 -0.115804 0.0248345 -0.0021906 -0.0161649 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 -0.00352879 -0.853642 399.813 -7.45541 100.161 +EDGE_SE3:QUAT 2063 2113 -0.130455 -2.92247 -0.0128724 0.0194339 -0.00253406 -0.00186127 0.999806 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.857 -0.00480236 -1.24492 399.884 -5.82993 100.117 +EDGE_SE3:QUAT 2064 2114 0.261451 -3.10266 -0.0498864 0.0266013 -0.00317936 0.0282374 0.999242 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 -0.0116315 -2.03814 399.783 -7.96033 100.143 +EDGE_SE3:QUAT 2065 2115 0.0254718 -3.00189 0.0231042 0.0328293 0.00701379 0.0047252 0.999425 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.0223955 3.41092 399.657 -9.849 100.354 +EDGE_SE3:QUAT 2066 2116 -0.049218 -3.13552 0.0189291 0.0258074 0.000797796 0.00119519 0.999666 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.00189831 0.380156 399.8 -7.73982 100.2 +EDGE_SE3:QUAT 2067 2117 -0.107908 -2.88364 0.0978589 0.032666 0.00524755 0.00349542 0.999446 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 0.0165408 2.55297 399.669 -9.79761 100.337 +EDGE_SE3:QUAT 2068 2118 0.0766294 -3.06592 -0.154883 0.0306952 0.00280821 0.0424969 0.998621 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 0.000730789 0.61867 399.715 -9.23083 100.105 +EDGE_SE3:QUAT 2069 2119 -0.18226 -2.96298 -0.220603 0.0299556 0.00657345 0.00194208 0.999528 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 0.0194867 3.24964 399.714 -8.98425 100.299 +EDGE_SE3:QUAT 2070 2120 0.133802 -2.89555 -0.130823 0.0306445 0.00826771 -0.018521 0.999325 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 0.0262124 4.47084 399.689 -9.15715 100.301 +EDGE_SE3:QUAT 2071 2121 0.0431569 -3.14066 -0.147187 0.036483 0.0146721 0.0132689 0.999138 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.721 0.0550096 7.04043 399.518 -10.9713 100.524 +EDGE_SE3:QUAT 2072 2122 0.0265842 -3.16831 0.00734246 0.0195167 -0.0105687 -0.0164779 0.999618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.981 -0.0225253 -5.09007 399.842 -5.88743 100.161 +EDGE_SE3:QUAT 2073 2123 0.000393012 -2.99798 0.0855685 0.0253837 0.000352136 -0.0359123 0.999032 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.745 0.00540271 0.72237 399.806 -7.61172 100.065 +EDGE_SE3:QUAT 2074 2124 -0.0254687 -3.02397 -0.20654 0.0337311 -0.00612462 0.0211284 0.999189 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.61 -0.0236453 -3.486 399.642 -10.0873 100.329 +EDGE_SE3:QUAT 2075 2125 -0.0102956 -3.03346 -0.0513876 0.0348783 -0.00460191 0.00992149 0.999332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.547 -0.0179974 -2.50601 399.626 -10.4475 100.372 +EDGE_SE3:QUAT 2076 2126 0.0476452 -3.0611 -0.282201 0.0314258 0.00790412 -0.00880895 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 0.0255276 4.11533 399.678 -9.40771 100.335 +EDGE_SE3:QUAT 2077 2127 -0.0510679 -2.99195 -0.320886 0.0279886 -0.00545139 -0.0294468 0.99916 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.71 -0.0117166 -2.22752 399.755 -8.4262 100.164 +EDGE_SE3:QUAT 2078 2128 0.01914 -3.14313 -0.0788628 0.0242652 -0.00576058 -0.0114904 0.999623 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.802 -0.0132376 -2.71143 399.811 -7.29028 100.185 +EDGE_SE3:QUAT 2079 2129 0.0908892 -2.9919 -0.0835521 0.0412221 0.00337326 -0.0288268 0.998728 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.352 0.022528 2.39541 399.484 -12.3377 100.441 +EDGE_SE3:QUAT 2080 2130 -0.0279914 -2.86856 -0.011704 0.0299698 -0.00526741 0.0257151 0.999206 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.018671 -3.09265 399.718 -8.95996 100.228 +EDGE_SE3:QUAT 2081 2131 -0.041066 -3.00748 -0.119344 0.0283126 0.00979069 -0.0145708 0.999445 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 0.0273745 5.14032 399.72 -8.45996 100.291 +EDGE_SE3:QUAT 2082 2132 -0.114778 -3.13531 -0.0993181 0.0227098 0.016607 0.0216863 0.999369 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 400.123 0.0458583 8.00759 399.739 -6.87915 100.291 +EDGE_SE3:QUAT 2083 2133 -0.0300311 -3.04495 -0.170569 0.032769 0.00322752 -0.0201665 0.999254 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.592 0.0143224 2.00805 399.673 -9.81268 100.292 +EDGE_SE3:QUAT 2084 2134 -0.233249 -2.98449 -0.139945 0.0275725 0.000823619 -0.0217945 0.999382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 0.0054942 0.771769 399.771 -8.26562 100.182 +EDGE_SE3:QUAT 2085 2135 -0.156357 -3.00282 -0.00552253 0.0341372 -0.00172139 0.00279652 0.999412 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.538 -0.00649806 -0.917056 399.649 -10.2341 100.351 +EDGE_SE3:QUAT 2086 2136 -0.0496582 -3.02762 -0.129938 0.0224806 -0.000782545 0.0439995 0.998778 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 -0.00592963 -0.983432 399.847 -6.73769 99.9602 +EDGE_SE3:QUAT 2087 2137 -0.161622 -2.94154 -0.0194867 0.0193666 0.0100098 -0.00835978 0.999727 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.986 0.0185138 5.10191 399.847 -5.79075 100.178 +EDGE_SE3:QUAT 2088 2138 -0.120914 -3.04911 -0.0946241 0.0230044 -0.00526123 -0.00501597 0.999709 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.822 -0.0118091 -2.56031 399.83 -6.90436 100.175 +EDGE_SE3:QUAT 2089 2139 -0.19102 -3.08136 -0.0237986 0.0251246 -0.000512305 0.0148437 0.999574 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.749 -0.00313633 -0.47966 399.81 -7.53373 100.168 +EDGE_SE3:QUAT 2090 2140 -0.170683 -2.81957 -0.262863 0.037337 -0.00561133 0.00235447 0.999284 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.485 -0.0214371 -2.85519 399.569 -11.1897 100.44 +EDGE_SE3:QUAT 2091 2141 0.0408146 -3.10091 -0.0220481 0.030641 0.00226884 0.00943431 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 0.00523327 0.959993 399.717 -9.19232 100.276 +EDGE_SE3:QUAT 2092 2142 0.254939 -3.03945 -0.131421 0.0335753 0.00149925 -0.0315346 0.998937 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 0.0117295 1.38307 399.66 -10.0589 100.243 +EDGE_SE3:QUAT 2093 2143 -0.0833379 -2.95533 -0.121737 0.0345543 -0.000838811 -0.010244 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.000450218 -0.206622 399.642 -10.362 100.348 +EDGE_SE3:QUAT 2094 2144 -0.119895 -3.15628 -0.11941 0.0311125 -0.00686709 -0.0017244 0.999491 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 -0.021171 -3.39891 399.691 -9.33051 100.323 +EDGE_SE3:QUAT 2095 2145 -0.060066 -2.89078 -0.266169 0.0327279 -0.00024976 -0.0136449 0.999371 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.572 0.00210466 0.14309 399.679 -9.81411 100.303 +EDGE_SE3:QUAT 2096 2146 0.010105 -3.07861 -0.066546 0.0376594 -0.00479505 -0.0328358 0.998739 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.444 -0.00938704 -1.65083 399.567 -11.323 100.328 +EDGE_SE3:QUAT 2097 2147 -0.0671575 -2.98555 -0.223243 0.0290701 0.00719166 -0.00775571 0.999521 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 0.0214543 3.72889 399.725 -8.70507 100.286 +EDGE_SE3:QUAT 2098 2148 -0.102852 -2.91569 0.0028844 0.0351837 -0.00804265 -0.0228885 0.999086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.567 -0.0247093 -3.53256 399.605 -10.5849 100.357 +EDGE_SE3:QUAT 2099 2149 0.0340349 -3.19928 -0.0715693 0.0256119 0.00141211 0.00504455 0.999658 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.00296512 0.628123 399.802 -7.68247 100.195 +EDGE_SE3:QUAT 2100 2150 0.0117521 -3.04309 -0.0911104 0.0310008 -0.00462575 -0.00295931 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.642 -0.0138638 -2.25599 399.703 -9.29803 100.302 +EDGE_SE3:QUAT 2101 2151 0.00970708 -3.14109 -0.297364 0.0278595 0.00339655 -0.00127597 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 0.00962313 1.71848 399.762 -8.3535 100.241 +EDGE_SE3:QUAT 2102 2152 -0.0120343 -3.21792 -0.191891 0.0350955 -0.00364742 -0.0221737 0.999131 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 -0.00761959 -1.35425 399.626 -10.539 100.327 +EDGE_SE3:QUAT 2103 2153 -0.0482759 -3.12102 -0.127425 0.0388125 -0.00237718 -0.00594664 0.999226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.403 -0.00745775 -1.04854 399.546 -11.6377 100.452 +EDGE_SE3:QUAT 2104 2154 -0.0249924 -2.95525 -0.0808759 0.0319533 0.0111475 0.0145396 0.999321 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.734 0.0356782 5.29088 399.646 -9.61109 100.366 +EDGE_SE3:QUAT 2105 2155 -0.0253103 -3.07117 -0.0849674 0.0289211 0.00776481 -0.0158632 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.757 0.0231818 4.15485 399.724 -8.64696 100.272 +EDGE_SE3:QUAT 2106 2156 -0.00699182 -2.92859 -0.128395 0.0303547 0.00183743 -0.0132769 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.00788976 1.15955 399.722 -9.09749 100.262 +EDGE_SE3:QUAT 2107 2157 -0.0170204 -3.20539 -0.0960487 0.0285113 -0.00249644 -0.00996243 0.999541 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.681 -0.00557324 -1.07683 399.754 -8.55493 100.238 +EDGE_SE3:QUAT 2108 2158 0.204426 -3.10931 -0.0617148 0.0296978 0.00821361 0.0172737 0.999376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.72 0.023167 3.79546 399.71 -8.9329 100.277 +EDGE_SE3:QUAT 2109 2159 -0.150567 -3.05978 -0.0651103 0.031046 -0.00522922 -0.0230398 0.999239 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.637 -0.0125862 -2.18224 399.701 -9.33376 100.251 +EDGE_SE3:QUAT 2110 2160 0.256321 -2.90869 -0.231602 0.0349888 -0.00458433 0.0287222 0.998964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.556 -0.021381 -2.89091 399.622 -10.4645 100.306 +EDGE_SE3:QUAT 2111 2161 0.145595 -3.06737 -0.100928 0.0304405 0.00641468 0.0152764 0.999399 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 0.0176387 2.9254 399.707 -9.14708 100.28 +EDGE_SE3:QUAT 2112 2162 -0.102644 -3.04447 -0.132148 0.0349391 -0.000999389 0.0158586 0.999263 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 -0.00727954 -0.831331 399.633 -10.4725 100.343 +EDGE_SE3:QUAT 2113 2163 0.0106771 -2.97068 0.0332433 0.0321073 0.00203306 0.0301347 0.999028 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.588 0.000350445 0.434605 399.689 -9.64092 100.22 +EDGE_SE3:QUAT 2114 2164 0.153236 -3.11544 -0.0336354 0.0283416 0.00425954 -0.00958695 0.999543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.707 0.013244 2.29121 399.751 -8.49058 100.246 +EDGE_SE3:QUAT 2115 2165 -0.000287043 -2.98676 -0.147097 0.033057 -0.000350093 -0.0131893 0.999366 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.563 0.00172608 0.0866409 399.672 -9.9129 100.31 +EDGE_SE3:QUAT 2116 2166 0.00458294 -3.0702 -0.00728502 0.0261978 0.00489828 0.00592947 0.999627 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 0.0122497 2.35454 399.785 -7.86205 100.218 +EDGE_SE3:QUAT 2117 2167 0.061471 -3.15293 -0.0660774 0.0245225 -0.00177259 -0.00324547 0.999692 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 -0.00396838 -0.838072 399.818 -7.35565 100.181 +EDGE_SE3:QUAT 2118 2168 0.159012 -2.93752 -0.26102 0.0337405 -0.0014702 -0.0151318 0.999315 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.545 -0.00152766 -0.428003 399.658 -10.1212 100.319 +EDGE_SE3:QUAT 2119 2169 0.193779 -2.95555 0.00395872 0.027324 -0.00706823 -0.0061172 0.999583 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.762 -0.0189261 -3.4319 399.757 -8.20186 100.254 +EDGE_SE3:QUAT 2120 2170 -0.0198997 -3.20647 -0.0217357 0.0213653 -0.00168272 -0.0026615 0.999767 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.821 -0.00336189 -0.806905 399.862 -6.409 100.138 +EDGE_SE3:QUAT 2121 2171 -0.139601 -3.16729 -0.106272 0.0265796 -0.00208518 0.0273048 0.999272 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 -0.00898512 -1.47652 399.786 -7.96048 100.143 +EDGE_SE3:QUAT 2122 2172 0.00951113 -3.08614 -0.0493098 0.0340392 -0.0081146 0.00942079 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 -0.0286031 -4.2462 399.625 -10.1889 100.388 +EDGE_SE3:QUAT 2123 2173 0.132089 -2.95522 -0.112685 0.036455 0.00184875 -0.0120516 0.999261 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.476 0.00980661 1.18665 399.6 -10.9249 100.388 +EDGE_SE3:QUAT 2124 2174 0.118418 -3.04213 -0.0818185 0.0423721 0.00100007 -0.00677955 0.999078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.284 0.00663375 0.671465 399.461 -12.6989 100.535 +EDGE_SE3:QUAT 2125 2175 0.0139486 -3.06089 -0.0375995 0.0267951 0.00306994 -0.0138689 0.99954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 0.00990698 1.7567 399.78 -8.02713 100.204 +EDGE_SE3:QUAT 2126 2176 -0.113293 -3.0193 -0.0628315 0.029237 -0.00820338 -0.00566096 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 -0.0236875 -4.00001 399.717 -8.77526 100.299 +EDGE_SE3:QUAT 2127 2177 0.0950199 -2.96638 -0.0580626 0.0205513 0.00630827 0.041123 0.998923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.865 0.0116147 2.6416 399.859 -6.21732 99.9795 +EDGE_SE3:QUAT 2128 2178 0.0648743 -2.75039 0.13961 0.0274153 0.00494898 0.0169771 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.723 0.0116041 2.19313 399.766 -8.23828 100.211 +EDGE_SE3:QUAT 2129 2179 -0.0135544 -3.02566 -0.00291222 0.0292394 0.000500139 0.0302496 0.999114 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.658 -0.00370047 -0.280706 399.743 -8.77243 100.165 +EDGE_SE3:QUAT 2130 2180 0.105597 -3.10984 -0.105639 0.0401762 0.00185202 -0.0226246 0.998935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.366 0.0143877 1.4693 399.513 -12.0355 100.438 +EDGE_SE3:QUAT 2131 2181 0.154913 -2.81921 -0.0794897 0.0320919 0.00245594 0.025167 0.999165 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.59 0.0027922 0.741805 399.689 -9.63592 100.248 +EDGE_SE3:QUAT 2132 2182 0.0572089 -3.08445 0.0161857 0.028943 -0.0119401 -0.0391229 0.998744 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.803 -0.0360809 -5.28017 399.697 -8.77244 100.183 +EDGE_SE3:QUAT 2133 2183 0.20885 -3.20112 -0.112124 0.0288749 0.00296393 0.00654297 0.999557 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.00754488 1.3675 399.747 -8.66262 100.251 +EDGE_SE3:QUAT 2134 2184 -0.00756476 -3.02709 -0.190457 0.0358999 -0.00062039 0.0184382 0.999185 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.487 -0.00691143 -0.706689 399.613 -10.7613 100.354 +EDGE_SE3:QUAT 2135 2185 -0.192417 -3.10896 -0.0359544 0.0379344 0.00605622 -0.00731238 0.999235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.478 0.0245159 3.19088 399.553 -11.3622 100.454 +EDGE_SE3:QUAT 2136 2186 -0.0432472 -3.04974 0.0556173 0.025839 0.00318996 0.00184186 0.999659 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 0.00802128 1.56552 399.796 -7.75009 100.207 +EDGE_SE3:QUAT 2137 2187 0.192097 -3.03517 -0.228358 0.0268716 0.0114781 -0.0226705 0.999316 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.908 0.028234 6.10141 399.728 -8.00432 100.266 +EDGE_SE3:QUAT 2138 2188 -0.0177225 -3.05202 -0.22512 0.0268207 0.011684 -0.0178136 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.91 0.0292603 6.12649 399.727 -7.99921 100.286 +EDGE_SE3:QUAT 2139 2189 -0.0492927 -3.15565 -0.0285129 0.0266043 0.00240476 -0.00600156 0.999625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 0.00716772 1.29739 399.785 -7.9755 100.213 +EDGE_SE3:QUAT 2140 2190 0.101683 -2.87027 0.0241184 0.0328391 0.00474192 0.00417143 0.999441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.595 0.0148091 2.28662 399.668 -9.84988 100.337 +EDGE_SE3:QUAT 2141 2191 -0.00193299 -3.18117 -0.137418 0.0292972 0.00209823 -0.000938499 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 0.00629116 1.06482 399.741 -8.78491 100.261 +EDGE_SE3:QUAT 2142 2192 0.0371219 -3.0515 -0.103975 0.0298405 -0.00378674 0.000875768 0.999547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.011419 -1.90763 399.727 -8.94719 100.277 +EDGE_SE3:QUAT 2143 2193 0.115534 -3.02731 -0.110445 0.0396016 0.00289111 -0.0337833 0.99864 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.401 0.0208596 2.24424 399.524 -11.8533 100.368 +EDGE_SE3:QUAT 2144 2194 0.0262407 -2.98219 -0.140879 0.0274812 -0.00472465 -0.0351073 0.998994 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 -0.00850442 -1.77965 399.766 -8.27587 100.114 +EDGE_SE3:QUAT 2145 2195 -0.0639281 -3.11846 -0.354936 0.0358658 0.00116804 0.0219404 0.999115 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.485 -0.00146082 0.111221 399.614 -10.7588 100.338 +EDGE_SE3:QUAT 2146 2196 -0.0161992 -2.93174 -0.131956 0.0314237 -0.00308429 -0.00946324 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.614 -0.00793617 -1.36232 399.7 -9.42824 100.293 +EDGE_SE3:QUAT 2147 2197 -0.0479604 -2.94527 0.0440888 0.029757 -0.00550727 0.0316002 0.999042 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.705 -0.0195519 -3.31341 399.72 -8.88888 100.194 +EDGE_SE3:QUAT 2148 2198 0.0559343 -3.08769 -0.206948 0.0333138 0.0159848 0.0152282 0.999201 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.859 0.0567285 7.68453 399.568 -10.0316 100.479 +EDGE_SE3:QUAT 2149 2199 -0.187 -2.95398 -0.113378 0.0379161 0.000513279 0.019685 0.999087 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.425 -0.00371312 -0.191337 399.569 -11.3694 100.393 +EDGE_SE3:QUAT 2150 2200 0.0612344 -3.01045 -0.174001 0.0213249 0.000559685 0.0588524 0.998039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.00409645 -0.473176 399.863 -6.40627 99.7907 +EDGE_SE3:QUAT 2151 2201 -0.0819293 -2.96053 -0.156127 0.0260912 -0.00939447 -0.0301258 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.817 -0.0243641 -4.22006 399.763 -7.88105 100.167 +EDGE_SE3:QUAT 2152 2202 -0.171209 -3.11954 -0.167808 0.0215026 0.00149564 0.0272701 0.999396 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.815 0.000725676 0.395326 399.861 -6.45823 100.065 +EDGE_SE3:QUAT 2153 2203 -0.000337496 -2.99622 0.00581779 0.017685 -0.00803405 -0.0218277 0.999573 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.948 -0.0151333 -3.78332 399.882 -5.33937 100.088 +EDGE_SE3:QUAT 2154 2204 -0.168527 -3.13153 -0.145714 0.0261458 -0.0013691 -0.0220867 0.999413 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.727 -0.000576154 -0.337477 399.794 -7.84774 100.157 +EDGE_SE3:QUAT 2155 2205 -0.102031 -3.02013 -0.108693 0.0227718 0.0058853 0.00266264 0.99972 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.836 0.0132911 2.90522 399.831 -6.83234 100.179 +EDGE_SE3:QUAT 2156 2206 -0.0961555 -3.0657 -0.00638748 0.0368751 -0.00341422 -0.00209715 0.999312 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 -0.0120327 -1.6587 399.588 -11.0561 100.415 +EDGE_SE3:QUAT 2157 2207 0.128899 -3.02135 -0.0742188 0.0238493 -0.00320417 -0.0105445 0.999655 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.783 -0.00659821 -1.45029 399.826 -7.1595 100.166 +EDGE_SE3:QUAT 2158 2208 0.0492144 -3.08501 -0.160657 0.0210955 0.00835152 0.00185992 0.999741 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.911 0.0177137 4.15153 399.839 -6.32927 100.182 +EDGE_SE3:QUAT 2159 2209 0.106064 -3.24122 -0.200244 0.0360872 -0.00364772 -0.0313378 0.998851 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.484 -0.0052902 -1.14209 399.605 -10.8436 100.298 +EDGE_SE3:QUAT 2160 2210 -0.0397761 -3.14273 -0.142255 0.0230627 0.00260068 0.0376877 0.99902 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.789 0.00216081 0.776886 399.838 -6.93818 100.02 +EDGE_SE3:QUAT 2161 2211 0.0641557 -3.12435 -0.0299417 0.0349618 -0.000671412 -0.00876267 0.99935 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 -0.000202404 -0.151578 399.633 -10.4834 100.359 +EDGE_SE3:QUAT 2162 2212 -0.041255 -3.08557 -0.0228275 0.043179 -0.00442478 -0.00467225 0.999047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.276 -0.017454 -2.08778 399.433 -12.9452 100.57 +EDGE_SE3:QUAT 2163 2213 0.0304574 -3.11691 -0.160732 0.0232168 -0.0074818 0.0188843 0.999524 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.869 -0.0172755 -4.00183 399.815 -6.93422 100.169 +EDGE_SE3:QUAT 2164 2214 0.108739 -3.00643 0.027084 0.0429182 0.00271704 -0.0176356 0.998919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.281 0.0177167 1.8098 399.443 -12.8543 100.53 +EDGE_SE3:QUAT 2165 2215 0.206983 -3.06189 -0.111523 0.0265382 -0.00517523 0.0132339 0.999547 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.0148588 -2.79656 399.777 -7.94458 100.215 +EDGE_SE3:QUAT 2166 2216 -0.038263 -3.10795 -0.172717 0.0205162 0.00150542 0.0181402 0.999624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.833 0.00159784 0.528959 399.873 -6.15934 100.094 +EDGE_SE3:QUAT 2167 2217 -0.0311467 -3.33994 -0.168698 0.0293197 -0.00238057 0.00989774 0.999518 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.666 -0.00854103 -1.36336 399.74 -8.78739 100.253 +EDGE_SE3:QUAT 2168 2218 0.0277269 -3.02926 -0.0189177 0.0381447 0.00112834 -0.0442446 0.998292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.432 0.0164603 1.57399 399.561 -11.4285 100.246 +EDGE_SE3:QUAT 2169 2219 -0.132009 -3.20052 -0.124892 0.037666 0.00454092 -0.00945374 0.999235 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.465 0.0193394 2.48116 399.565 -11.2827 100.433 +EDGE_SE3:QUAT 2170 2220 0.0515657 -3.19811 -0.0226816 0.0361189 0.00147326 -0.0120091 0.999274 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.484 0.00835749 0.995814 399.607 -10.8252 100.379 +EDGE_SE3:QUAT 2171 2221 0.0020289 -3.0789 -0.105971 0.0321171 0.00131317 0.031703 0.99898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 -0.00233039 0.0448689 399.69 -9.6401 100.209 +EDGE_SE3:QUAT 2172 2222 -0.089643 -3.07374 0.0917028 0.0361484 0.0100717 -0.00265491 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.612 0.0366561 5.08932 399.567 -10.8293 100.463 +EDGE_SE3:QUAT 2173 2223 0.0348587 -3.13613 -0.181005 0.0352175 0.00372214 -0.0105812 0.999317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.527 0.0153834 2.08243 399.622 -10.5506 100.372 +EDGE_SE3:QUAT 2174 2224 -0.00313106 -3.06027 -0.147292 0.0415302 0.00369252 -0.0445906 0.998135 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.359 0.028056 2.95031 399.473 -12.4184 100.339 +EDGE_SE3:QUAT 2175 2225 -0.175605 -3.17031 -0.199502 0.0245399 0.00031297 0.00195783 0.999697 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 0.000531606 0.127579 399.819 -7.35988 100.18 +EDGE_SE3:QUAT 2176 2226 -0.0534163 -3.00006 0.0805199 0.0282536 0.00265502 0.0232901 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.684 0.0039268 0.931271 399.758 -8.48574 100.188 +EDGE_SE3:QUAT 2177 2227 0.0729397 -3.10352 -0.257411 0.0253046 0.0118392 0.00479205 0.999598 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.921 0.030642 5.8461 399.752 -7.5977 100.286 +EDGE_SE3:QUAT 2178 2228 -0.129155 -3.00117 -0.209532 0.0317819 -0.00194833 -0.00631725 0.999473 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.00493848 -0.85283 399.696 -9.53221 100.301 +EDGE_SE3:QUAT 2179 2229 -0.113299 -3.05684 -0.210092 0.0238167 0.00206004 0.0143417 0.999611 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.776 0.00334724 0.82442 399.828 -7.1491 100.152 +EDGE_SE3:QUAT 2180 2230 -0.0189862 -3.10925 0.00164508 0.0376104 -0.00397927 -0.0246591 0.99898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.443 -0.00833789 -1.42994 399.57 -11.2957 100.371 +EDGE_SE3:QUAT 2181 2231 -0.0587379 -3.11642 -0.124486 0.0316236 0.00730937 0.0162509 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 0.0211815 3.34277 399.68 -9.50542 100.307 +EDGE_SE3:QUAT 2182 2232 -0.0113093 -3.08881 -0.0505008 0.0361348 0.00507421 -0.00370021 0.999327 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.514 0.0190915 2.61454 399.598 -10.8289 100.409 +EDGE_SE3:QUAT 2183 2233 0.0726105 -3.07909 -0.0203768 0.0208267 0.000438904 -0.003979 0.999775 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.827 0.0012564 0.269078 399.87 -6.24633 100.129 +EDGE_SE3:QUAT 2184 2234 -0.0302362 -3.11005 -0.154014 0.0298669 -0.00499919 0.00877547 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.68 -0.0160447 -2.6549 399.722 -8.9468 100.279 +EDGE_SE3:QUAT 2185 2235 0.15347 -2.98528 -0.0187968 0.0283963 0.00183575 -0.015083 0.999481 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.685 0.00749268 1.17394 399.756 -8.51011 100.223 +EDGE_SE3:QUAT 2186 2236 -0.0476083 -2.98281 -0.0224559 0.0254029 -0.00183605 -0.0341383 0.999093 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.742 -0.000296989 -0.396513 399.805 -7.63243 100.078 +EDGE_SE3:QUAT 2187 2237 -0.0408969 -3.07651 -0.124193 0.033732 -0.00327674 -0.00939089 0.999381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.555 -0.00903944 -1.44661 399.655 -10.1199 100.339 +EDGE_SE3:QUAT 2188 2238 -0.0176007 -2.96329 -0.182624 0.0243746 0.00142021 0.00268853 0.999698 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.765 0.00314723 0.670415 399.821 -7.31094 100.179 +EDGE_SE3:QUAT 2189 2239 -0.173644 -2.93198 -0.218538 0.0300674 0.00948874 -0.000386065 0.999503 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.756 0.0285835 4.74897 399.693 -9.01338 100.334 +EDGE_SE3:QUAT 2190 2240 -0.0104062 -3.19554 -0.0683765 0.0252371 0.000469855 0.0368703 0.999001 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.746 -0.00349364 -0.323423 399.809 -7.57389 100.055 +EDGE_SE3:QUAT 2191 2241 -0.079757 -3.04263 -0.129327 0.0275684 -0.00140088 -0.0258242 0.999285 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.696 5.21243e-05 -0.272583 399.771 -8.27552 100.162 +EDGE_SE3:QUAT 2192 2242 0.259483 -3.19725 -0.012703 0.0286898 0.00496268 0.0102979 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.698 0.0129281 2.30221 399.744 -8.6133 100.252 +EDGE_SE3:QUAT 2193 2243 0.252445 -2.99016 -0.0735526 0.0296618 -0.00177084 -0.00563065 0.999543 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.651 -0.00427888 -0.784519 399.735 -8.89662 100.263 +EDGE_SE3:QUAT 2194 2244 -0.0730365 -3.10255 -0.113453 0.0180847 -0.00381533 -0.000966621 0.999829 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.888 -0.00686099 -1.89671 399.896 -5.42506 100.108 +EDGE_SE3:QUAT 2195 2245 -0.0571928 -3.09838 -0.100858 0.0319514 0.0066534 0.0188151 0.99929 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.635 0.0186111 2.96235 399.678 -9.60526 100.297 +EDGE_SE3:QUAT 2196 2246 -0.0409103 -2.9799 -0.196964 0.0342372 -0.00160327 -0.0157696 0.999288 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 -0.00180952 -0.47682 399.648 -10.2706 100.328 +EDGE_SE3:QUAT 2197 2247 -0.133508 -3.32853 -0.069374 0.0366866 -0.00229513 -0.0325137 0.998795 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.461 0.000299778 -0.429963 399.595 -11.0154 100.3 +EDGE_SE3:QUAT 2198 2248 0.095991 -3.06765 0.0395367 0.0295812 -0.00242191 0.0137002 0.999466 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 -0.00934814 -1.45292 399.735 -8.86393 100.249 +EDGE_SE3:QUAT 2199 2249 0.00152709 -3.28254 -0.19906 0.0344058 -0.00359006 0.0248629 0.999092 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.556 -0.0172994 -2.30528 399.638 -10.2983 100.307 +EDGE_SE3:QUAT 2200 2250 0.0731715 -3.05511 -0.168677 0.0304798 0.00108712 0.0235138 0.999258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.628 -0.00105748 0.113029 399.721 -9.14564 100.224 +EDGE_SE3:QUAT 2201 2251 0.0318476 -3.08408 0.0372244 0.0277045 -0.00841853 -0.0122406 0.999506 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.775 -0.0228865 -4.00322 399.743 -8.32761 100.261 +EDGE_SE3:QUAT 2202 2252 0.135354 -3.00065 -0.070474 0.0231408 0.00381823 0.0451848 0.998703 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 0.00455458 1.27787 399.835 -6.97718 99.9627 +EDGE_SE3:QUAT 2203 2253 0.0621182 -2.99876 -0.126039 0.0283518 -0.00291763 0.0164436 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.695 -0.0105571 -1.73712 399.755 -8.49265 100.222 +EDGE_SE3:QUAT 2204 2254 0.141866 -3.13732 -0.194417 0.0392112 -0.00390948 0.0326833 0.998689 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.426 -0.0236857 -2.71878 399.53 -11.73 100.372 +EDGE_SE3:QUAT 2205 2255 -0.00107366 -3.00815 -0.0399029 0.0355883 -0.00378718 0.0181912 0.999194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.522 -0.0173985 -2.27929 399.613 -10.656 100.36 +EDGE_SE3:QUAT 2206 2256 -0.00468805 -2.9346 -0.340954 0.028735 -0.00882329 -0.0193345 0.999361 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.754 -0.024519 -4.07452 399.723 -8.65013 100.259 +EDGE_SE3:QUAT 2207 2257 -0.0641324 -3.197 -0.0476484 0.0297034 -0.012303 0.000465648 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.844 -0.0366454 -6.15819 399.675 -8.90257 100.371 +EDGE_SE3:QUAT 2208 2258 -0.0593136 -3.18147 -0.154494 0.0325757 -0.0030299 -0.000637302 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.587 -0.00972768 -1.5011 399.678 -9.76769 100.325 +EDGE_SE3:QUAT 2209 2259 0.122889 -3.17773 0.0533363 0.0304235 0.00813024 0.0270266 0.999139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.693 0.022256 3.56651 399.698 -9.16668 100.243 +EDGE_SE3:QUAT 2210 2260 0.0852201 -3.03755 -0.00071156 0.0325055 0.00735906 -0.0254866 0.999119 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.0261874 4.17182 399.659 -9.70839 100.298 +EDGE_SE3:QUAT 2211 2261 0.0888489 -2.96886 -0.0838832 0.0298264 0.00540709 0.000814799 0.99954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.682 0.0160138 2.68707 399.721 -8.94417 100.287 +EDGE_SE3:QUAT 2212 2262 -0.0848152 -2.93901 -0.11944 0.0263968 0.00114862 -0.0199454 0.999452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 0.00569978 0.889537 399.79 -7.91216 100.171 +EDGE_SE3:QUAT 2213 2263 -0.0982209 -3.02872 0.0709948 0.0259637 0.00862191 0.0142961 0.999523 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.816 0.0222152 4.0858 399.769 -7.81006 100.23 +EDGE_SE3:QUAT 2214 2264 0.170761 -3.07959 -0.187069 0.040708 0.000923353 -0.00795153 0.999139 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.34 0.00635642 0.65507 399.502 -12.2009 100.492 +EDGE_SE3:QUAT 2215 2265 0.0611452 -3.00291 -0.0804721 0.0244772 -0.00766514 -0.00964693 0.999624 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.83 -0.0185724 -3.6892 399.797 -7.35485 100.209 +EDGE_SE3:QUAT 2216 2266 0.0389333 -3.1105 -0.125301 0.0296811 -0.00451409 -0.0191667 0.999365 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.665 -0.0105237 -1.91339 399.728 -8.91791 100.239 +EDGE_SE3:QUAT 2217 2267 0.0530079 -3.1224 -0.106622 0.0368368 0.0011726 -0.0316957 0.998818 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.467 0.0125639 1.28509 399.591 -11.0378 100.31 +EDGE_SE3:QUAT 2218 2268 0.110224 -3.18825 -0.123779 0.0240453 -0.00557382 0.0136643 0.999602 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.816 -0.0141192 -2.98248 399.813 -7.19588 100.179 +EDGE_SE3:QUAT 2219 2269 0.0352732 -2.99297 -0.122349 0.0392969 -0.00330701 0.00542963 0.999207 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.399 -0.0145152 -1.7792 399.532 -11.7761 100.469 +EDGE_SE3:QUAT 2220 2270 -0.11259 -3.10774 0.00556954 0.0306387 -0.00952916 0.00924067 0.999442 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 -0.0293765 -4.93175 399.681 -9.16763 100.34 +EDGE_SE3:QUAT 2221 2271 0.0525041 -3.05159 -0.200526 0.0275735 -0.000931231 0.0145223 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 -0.00472234 -0.705395 399.771 -8.26644 100.208 +EDGE_SE3:QUAT 2222 2272 -0.0463186 -3.01473 -0.0436129 0.037469 -0.00505805 -0.0144717 0.99918 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.462 -0.0153659 -2.2003 399.57 -11.2473 100.415 +EDGE_SE3:QUAT 2223 2273 -0.201168 -3.11363 0.0762748 0.0241116 -0.00613739 0.0175628 0.999536 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.826 -0.0154705 -3.3208 399.809 -7.20941 100.173 +EDGE_SE3:QUAT 2224 2274 -0.00791141 -2.98722 -0.0521449 0.034859 -0.00039738 -0.0127452 0.999311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.514 0.00171383 0.0680057 399.635 -10.4526 100.348 +EDGE_SE3:QUAT 2225 2275 0.236758 -3.08478 -0.170701 0.0349375 0.00136393 0.0130611 0.999303 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.512 0.00158394 0.407443 399.633 -10.4787 100.35 +EDGE_SE3:QUAT 2226 2276 -0.0103581 -3.04668 -0.0377333 0.0341549 0.00647858 0.00285943 0.999391 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 0.0216511 3.17773 399.634 -10.2432 100.378 +EDGE_SE3:QUAT 2227 2277 0.153741 -3.04103 -0.125169 0.0308308 -0.0018154 -0.00158549 0.999522 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 -0.0052946 -0.877611 399.714 -9.24536 100.287 +EDGE_SE3:QUAT 2228 2278 0.142356 -3.12135 0.0522025 0.0376834 0.00655078 -0.0141236 0.999168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.501 0.0273823 3.59049 399.555 -11.2774 100.44 +EDGE_SE3:QUAT 2229 2279 -0.147522 -2.92637 -0.175416 0.0282844 0.0104438 0.0116643 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 0.0298663 5.02131 399.718 -8.5043 100.299 +EDGE_SE3:QUAT 2230 2280 -0.0262539 -3.24955 -0.281895 0.0282326 0.00196426 -0.0318635 0.999091 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.694 0.0101175 1.52002 399.758 -8.45513 100.143 +EDGE_SE3:QUAT 2231 2281 -0.0801277 -3.06658 0.0321917 0.0413025 0.00331754 0.0275859 0.99876 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.321 0.00445643 0.972022 399.485 -12.3999 100.44 +EDGE_SE3:QUAT 2232 2282 0.0209947 -3.17195 0.0299715 0.0332664 -0.00111484 -0.030647 0.998976 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.557 0.00308278 0.0548985 399.668 -9.98278 100.238 +EDGE_SE3:QUAT 2233 2283 0.0453151 -3.18292 -0.117051 0.024213 0.00696151 0.015157 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 0.0162554 3.25851 399.806 -7.28235 100.184 +EDGE_SE3:QUAT 2234 2284 -0.14367 -3.17219 -0.186889 0.0283584 -0.00795708 0.014591 0.99946 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.773 -0.0230807 -4.22421 399.732 -8.4797 100.268 +EDGE_SE3:QUAT 2235 2285 0.236379 -2.99963 -0.119173 0.0301125 0.00311501 -0.0115212 0.999475 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.654 0.0112028 1.76422 399.724 -9.02241 100.267 +EDGE_SE3:QUAT 2236 2286 0.213813 -3.05517 0.0100068 0.0260501 -0.00637522 -0.0263392 0.999293 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.766 -0.0145174 -2.77242 399.782 -7.84627 100.158 +EDGE_SE3:QUAT 2237 2287 -0.0393351 -2.88869 0.0161872 0.0301356 -0.00510517 -0.00248901 0.99953 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.669 -0.0150322 -2.50571 399.717 -9.03856 100.29 +EDGE_SE3:QUAT 2238 2288 0.0736107 -3.12632 0.152321 0.0272433 0.00496994 0.0189603 0.999437 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.726 0.0113727 2.17281 399.768 -8.18889 100.201 +EDGE_SE3:QUAT 2239 2289 -0.075851 -3.08171 -0.142838 0.0332635 -0.00295561 -0.015367 0.999324 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.564 -0.00656943 -1.16948 399.665 -9.98285 100.313 +EDGE_SE3:QUAT 2240 2290 -0.107804 -3.19145 -0.167181 0.0364426 0.0120134 0.0272477 0.998892 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.615 0.0424265 5.40204 399.549 -10.989 100.411 +EDGE_SE3:QUAT 2241 2291 0.148737 -2.87134 -0.122466 0.0321249 0.000121748 0.030532 0.999017 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.589 -0.00586051 -0.527354 399.69 -9.6347 100.217 +EDGE_SE3:QUAT 2242 2292 -0.0546812 -2.88389 -0.0250769 0.0380122 -0.00580738 0.0283722 0.998858 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.49 -0.0277588 -3.54516 399.55 -11.3626 100.385 +EDGE_SE3:QUAT 2243 2293 -0.00924392 -3.19348 -0.127155 0.0337894 0.0103738 0.0081433 0.999342 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.0347281 5.01793 399.616 -10.1454 100.408 +EDGE_SE3:QUAT 2244 2294 0.0739248 -2.9843 -0.13323 0.0290308 0.00727809 0.0255518 0.999225 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 0.0187268 3.18967 399.728 -8.74279 100.219 +EDGE_SE3:QUAT 2245 2295 -0.0400843 -3.15058 -0.119844 0.0270829 0.00118788 0.0364888 0.998966 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.706 -0.00214229 0.000308919 399.779 -8.13237 100.087 +EDGE_SE3:QUAT 2246 2296 -0.0364043 -3.02858 0.107759 0.0385736 -0.00806006 -0.00379973 0.999216 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.485 -0.0303656 -3.93751 399.528 -11.5678 100.489 +EDGE_SE3:QUAT 2247 2297 -0.0406195 -3.08942 -0.129353 0.0333019 -0.00342638 -0.0155353 0.999319 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.566 -0.00817052 -1.40086 399.663 -9.99587 100.315 +EDGE_SE3:QUAT 2248 2298 0.0284754 -2.96216 -0.0420628 0.0309219 0.0019635 -0.0090297 0.999479 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.625 0.00770342 1.14833 399.711 -9.26861 100.282 +EDGE_SE3:QUAT 2249 2299 -0.0193531 -3.1636 -0.175718 0.0393415 -0.000210873 -0.0120771 0.999153 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.381 0.00290668 0.179641 399.536 -11.7941 100.45 +EDGE_SE3:QUAT 2250 2300 0.0398398 -3.21735 -0.147889 0.0308061 0.00841708 -0.0183242 0.999322 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.73 0.0267502 4.54365 399.685 -9.20527 100.307 +EDGE_SE3:QUAT 2251 2301 -0.0816599 -3.05955 -0.158979 0.0229771 -0.00192909 -0.00958411 0.999688 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.792 -0.00346535 -0.831913 399.84 -6.89506 100.151 +EDGE_SE3:QUAT 2252 2302 -0.00257336 -3.1386 -0.280685 0.029354 0.00631106 -0.00837941 0.999514 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 0.0193157 3.30095 399.725 -8.79097 100.281 +EDGE_SE3:QUAT 2253 2303 0.132974 -3.00218 0.0359249 0.0378047 -0.00573633 1.8283e-05 0.999269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.471 -0.0216552 -2.86522 399.558 -11.3323 100.452 +EDGE_SE3:QUAT 2254 2304 0.0288848 -3.26039 0.134843 0.0204666 0.00123161 0.00298759 0.999785 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.834 0.00227574 0.578888 399.874 -6.13943 100.126 +EDGE_SE3:QUAT 2255 2305 -0.0724857 -3.02757 -0.0839962 0.0244118 -0.00549771 -0.00118979 0.999686 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.8 -0.0133422 -2.73024 399.809 -7.32211 100.2 +EDGE_SE3:QUAT 2256 2306 0.130484 -3.04301 -0.22685 0.0377646 0.00297708 -0.0215164 0.999051 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.451 0.016772 1.97337 399.567 -11.3089 100.391 +EDGE_SE3:QUAT 2257 2307 -0.0353496 -3.17349 -0.067022 0.028282 -0.00218781 0.00199097 0.999596 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.687 -0.00647916 -1.12691 399.758 -8.48024 100.243 +EDGE_SE3:QUAT 2258 2308 0.00969587 -3.079 -0.0460786 0.0200255 -0.00294403 -0.0195881 0.999603 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.847 -0.00454243 -1.2357 399.877 -6.01828 100.087 +EDGE_SE3:QUAT 2259 2309 -0.0836754 -3.00392 -0.154613 0.0268532 -0.00116563 0.00804184 0.999606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.714 -0.0042567 -0.711943 399.783 -8.05123 100.211 +EDGE_SE3:QUAT 2260 2310 0.100764 -3.00648 -0.0132723 0.0293034 0.00223363 -0.0151357 0.999453 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 0.00893272 1.38179 399.74 -8.78067 100.24 +EDGE_SE3:QUAT 2261 2311 0.0790994 -3.00102 -0.10434 0.0311696 0.00314036 -0.0181999 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.631 0.0128461 1.90868 399.704 -9.33509 100.268 +EDGE_SE3:QUAT 2262 2312 0.0899121 -3.07788 -0.029679 0.0411345 -0.0050569 -0.0146561 0.999033 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.346 -0.0162938 -2.16273 399.483 -12.3446 100.501 +EDGE_SE3:QUAT 2263 2313 -0.0698989 -2.95737 0.0834808 0.0409976 -0.00220328 -0.0337639 0.998586 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.327 0.00231937 -0.269077 399.494 -12.3061 100.392 +EDGE_SE3:QUAT 2264 2314 0.0671252 -3.11059 0.0243918 0.0251889 0.00309528 -0.0120915 0.999605 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.762 0.00906833 1.72933 399.805 -7.54675 100.184 +EDGE_SE3:QUAT 2265 2315 0.0467165 -3.03716 -0.104013 0.0284953 0.000786273 0.00760285 0.999565 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.675 0.00100673 0.262879 399.756 -8.5464 100.238 +EDGE_SE3:QUAT 2266 2316 0.047945 -3.09847 -0.171384 0.0289037 -0.000896498 0.0130005 0.999497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.00471827 -0.673231 399.749 -8.66537 100.235 +EDGE_SE3:QUAT 2267 2317 0.0292439 -3.11168 -0.0168262 0.0304461 0.00323234 -0.00696432 0.999507 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.645 0.0109678 1.74201 399.717 -9.1249 100.281 +EDGE_SE3:QUAT 2268 2318 -0.145639 -3.23678 -0.071963 0.0319625 -0.00638646 -0.00590589 0.999451 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 -0.0195984 -3.07736 399.678 -9.59053 100.33 +EDGE_SE3:QUAT 2269 2319 -0.00823403 -3.01181 -0.284541 0.0317998 -0.0133073 -0.0123807 0.999329 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.807 -0.0436721 -6.41404 399.628 -9.5643 100.406 +EDGE_SE3:QUAT 2270 2320 0.0966246 -3.09019 -0.119338 0.0357637 -0.00555087 -0.00202539 0.999343 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.527 -0.0194145 -2.72907 399.604 -10.7237 100.404 +EDGE_SE3:QUAT 2271 2321 0.0643968 -2.99221 -0.0939419 0.020839 0.00559024 0.0145229 0.999662 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.861 0.0111105 2.61218 399.858 -6.26638 100.129 +EDGE_SE3:QUAT 2272 2322 -0.141084 -3.40945 -0.186194 0.0314848 0.00119621 0.0168018 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.604 0.000439928 0.280152 399.702 -9.4452 100.27 +EDGE_SE3:QUAT 2273 2323 -0.0304286 -3.19964 -0.028086 0.0214579 -0.000651452 -0.0161182 0.99964 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.816 8.55319e-05 -0.118047 399.862 -6.43826 100.112 +EDGE_SE3:QUAT 2274 2324 -0.0755028 -3.03482 -0.277086 0.0363546 -0.00352291 -0.00905804 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.483 -0.0105471 -1.56179 399.599 -10.9054 100.396 +EDGE_SE3:QUAT 2275 2325 -0.0249669 -3.13455 -0.0897277 0.036927 -0.000385112 -0.0345639 0.99872 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.456 0.00794224 0.573042 399.59 -11.0754 100.29 +EDGE_SE3:QUAT 2276 2326 0.00886406 -3.00058 -0.232417 0.0290978 0.00133159 0.0216768 0.999341 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.661 0.000213407 0.286726 399.745 -8.73208 100.208 +EDGE_SE3:QUAT 2277 2327 -0.0573412 -3.12541 -0.0248082 0.0421323 -0.00277108 -0.00333981 0.999103 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.299 -0.0104929 -1.29896 399.465 -12.6301 100.536 +EDGE_SE3:QUAT 2278 2328 0.151406 -3.14626 -0.0649404 0.0287369 -0.00432172 0.00866591 0.99954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.698 -0.0135107 -2.30867 399.744 -8.60968 100.255 +EDGE_SE3:QUAT 2279 2329 0.208943 -3.24225 -0.0761318 0.038978 -0.00829189 -0.0381324 0.998478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.441 -0.023686 -3.24423 399.521 -11.7493 100.345 +EDGE_SE3:QUAT 2280 2330 0.103572 -2.96804 -0.262925 0.0376889 -0.00403249 -0.00747159 0.999253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.449 -0.0132266 -1.84477 399.568 -11.3044 100.431 +EDGE_SE3:QUAT 2281 2331 0.0703312 -3.1521 -0.214529 0.0339254 -0.00137868 -0.0202438 0.999218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.54 -2.1871e-05 -0.276516 399.654 -10.178 100.305 +EDGE_SE3:QUAT 2282 2332 -0.05575 -2.95984 -0.0271593 0.0267517 -0.000259383 -0.0326816 0.999108 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.715 0.00395641 0.394778 399.785 -8.02574 100.108 +EDGE_SE3:QUAT 2283 2333 -0.104201 -3.05546 0.0934701 0.0246429 -0.00303134 0.0099286 0.999642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 -0.00847518 -1.66154 399.814 -7.38454 100.18 +EDGE_SE3:QUAT 2284 2334 -0.0957512 -3.13413 -0.124297 0.0300558 0.000154613 0.00110076 0.999548 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.639 0.000265105 0.0573989 399.729 -9.01271 100.271 +EDGE_SE3:QUAT 2285 2335 0.0349026 -3.05373 -0.0246602 0.0343018 -0.00269992 0.00323346 0.999403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.54 -0.00995651 -1.41508 399.644 -10.2825 100.357 +EDGE_SE3:QUAT 2286 2336 -0.0229829 -2.98571 0.0127402 0.0289538 0.00269032 -0.0055986 0.999561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.00863444 1.44139 399.745 -8.67936 100.254 +EDGE_SE3:QUAT 2287 2337 0.204578 -3.19282 -0.0232178 0.0314058 0.00624643 -0.00840652 0.999452 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.662 0.0206234 3.27911 399.688 -9.40571 100.318 +EDGE_SE3:QUAT 2288 2338 -0.00919614 -3.10004 -0.166525 0.0326908 0.00193092 -0.018818 0.999286 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.582 0.0100908 1.33319 399.677 -9.79515 100.29 +EDGE_SE3:QUAT 2289 2339 0.0794072 -3.05918 -0.13434 0.0324594 -0.000921857 -0.00485361 0.999461 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.579 -0.00196866 -0.365989 399.684 -9.73361 100.314 +EDGE_SE3:QUAT 2290 2340 0.124318 -2.95537 -0.247582 0.0291583 0.00310137 -0.000525649 0.99957 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.673 0.00911121 1.55875 399.741 -8.74324 100.262 +EDGE_SE3:QUAT 2291 2341 0.158017 -2.99723 -0.0902945 0.0317198 -0.00260085 -0.000270461 0.999493 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.606 -0.00818421 -1.29413 399.695 -9.51112 100.307 +EDGE_SE3:QUAT 2292 2342 -0.0838912 -3.144 -0.17146 0.0307961 0.000892018 0.0209012 0.999307 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 -0.00122069 0.059426 399.715 -9.23883 100.241 +EDGE_SE3:QUAT 2293 2343 -0.0562223 -3.12942 -0.12547 0.0211485 -0.00118645 0.00527904 0.999762 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.823 -0.00296291 -0.65995 399.865 -6.34188 100.133 +EDGE_SE3:QUAT 2294 2344 -0.0813901 -3.24565 -0.0308521 0.0368554 -0.0078286 0.00659822 0.999268 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.543 -0.0298622 -4.05617 399.567 -11.0371 100.448 +EDGE_SE3:QUAT 2295 2345 -0.0449535 -3.18971 -0.0162136 0.0244103 0.00631827 0.0134627 0.999591 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.806 0.0146779 2.96013 399.806 -7.33749 100.186 +EDGE_SE3:QUAT 2296 2346 0.00695177 -2.94834 -0.165641 0.0239007 0.00165944 0.022592 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 0.0014261 0.50505 399.828 -7.17624 100.121 +EDGE_SE3:QUAT 2297 2347 -0.0419891 -3.27378 -0.0566923 0.0171207 0.00184838 -0.00452785 0.999841 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.888 0.00339808 0.970449 399.911 -5.13374 100.088 +EDGE_SE3:QUAT 2298 2348 -0.0643839 -3.17814 -0.0325685 0.0389546 0.00663154 0.0189645 0.999039 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.433 0.0211797 2.86746 399.529 -11.7024 100.445 +EDGE_SE3:QUAT 2299 2349 0.155101 -2.99267 -0.0575645 0.0431298 0.00670722 0.000544198 0.999047 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.314 0.0287105 3.33443 399.424 -12.9262 100.589 +EDGE_SE3:QUAT 2300 2350 0.0143483 -3.15621 -0.235278 0.0347783 -0.000837321 -0.00346565 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.517 -0.00207028 -0.345912 399.637 -10.4278 100.362 +EDGE_SE3:QUAT 2301 2351 0.025686 -3.18099 0.0236252 0.018729 -0.000480412 -0.0115445 0.999758 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.86 -9.05053e-05 -0.110393 399.895 -5.61893 100.092 +EDGE_SE3:QUAT 2302 2352 0.13058 -3.00536 -0.0259078 0.0325858 -0.0050434 -0.0122608 0.999381 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.601 -0.0142747 -2.27947 399.672 -9.78265 100.319 +EDGE_SE3:QUAT 2303 2353 0.098438 -3.04361 -0.17478 0.02684 -0.00128685 -0.00993466 0.99959 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 -0.00203561 -0.483007 399.783 -8.05177 100.207 +EDGE_SE3:QUAT 2304 2354 0.151689 -3.09663 -0.154184 0.0318364 -0.000440887 0.0134766 0.999402 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.596 -0.00411124 -0.477534 399.696 -9.54515 100.286 +EDGE_SE3:QUAT 2305 2355 0.0301554 -2.87532 -0.133801 0.0416076 0.000219069 0.0159749 0.999006 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.308 -0.00461115 -0.289206 399.481 -12.4727 100.494 +EDGE_SE3:QUAT 2306 2356 -0.0436607 -3.11451 0.0256047 0.0348476 -0.000866775 0.0214616 0.999162 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.519 -0.00811333 -0.881228 399.635 -10.4449 100.32 +EDGE_SE3:QUAT 2307 2357 0.137609 -3.01303 -0.0444566 0.0292308 -0.00240288 -0.0131545 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 -0.00485766 -0.969706 399.742 -8.77197 100.242 +EDGE_SE3:QUAT 2308 2358 -0.00199259 -2.99604 -0.0836797 0.0316445 0.00357102 -0.0187608 0.999317 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.624 0.0144397 2.13954 399.694 -9.47533 100.277 +EDGE_SE3:QUAT 2309 2359 0.0820049 -3.06322 -0.112748 0.0349809 0.0034015 -0.0135096 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.532 0.014808 1.98213 399.628 -10.4786 100.359 +EDGE_SE3:QUAT 2310 2360 -0.0647832 -3.10886 -0.115426 0.0331649 -0.00173719 -0.0197617 0.999253 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.561 -0.00143902 -0.474386 399.669 -9.95148 100.292 +EDGE_SE3:QUAT 2311 2361 0.0559606 -2.90588 0.111901 0.0253616 -0.00262913 -0.0167842 0.999534 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.748 -0.00464165 -1.05815 399.805 -7.61513 100.168 +EDGE_SE3:QUAT 2312 2362 0.163394 -3.18081 0.00789267 0.0310593 0.00231327 0.00462236 0.999504 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.62 0.00631931 1.06951 399.709 -9.31536 100.291 +EDGE_SE3:QUAT 2313 2363 0.0507714 -3.06287 -0.139605 0.0239289 0.000699503 -0.00681073 0.99969 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.772 0.00244223 0.447322 399.828 -7.17569 100.168 +EDGE_SE3:QUAT 2314 2364 0.0742564 -2.93125 0.00617903 0.02592 0.00221747 0.0161466 0.999531 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.735 0.00366038 0.856779 399.797 -7.78083 100.178 +EDGE_SE3:QUAT 2315 2365 0.00331017 -3.09833 -0.0890589 0.0261048 -0.00842266 0.027709 0.99924 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.842 -0.0215737 -4.64117 399.765 -7.78147 100.185 +EDGE_SE3:QUAT 2316 2366 0.0290666 -3.13497 -0.21771 0.0338579 0.00416086 0.0197483 0.999223 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.555 0.00994845 1.67662 399.65 -10.1683 100.314 +EDGE_SE3:QUAT 2317 2367 -0.262747 -3.00601 -0.158514 0.0336692 -0.0047829 -0.0134017 0.999332 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 -0.0134813 -2.11812 399.652 -10.1077 100.336 +EDGE_SE3:QUAT 2318 2368 0.0425717 -3.2411 -0.158981 0.038406 -0.00724926 -0.00858655 0.999199 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.47 -0.0260059 -3.42234 399.537 -11.5245 100.469 +EDGE_SE3:QUAT 2319 2369 -0.141221 -3.04945 -0.0539595 0.0218844 -0.00337234 -0.0172691 0.999606 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.819 -0.00599178 -1.45833 399.852 -6.57557 100.12 +EDGE_SE3:QUAT 2320 2370 0.0549081 -3.24491 -0.12199 0.0302628 -0.00590167 0.0206727 0.999311 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.693 -0.0200297 -3.32304 399.71 -9.04995 100.261 +EDGE_SE3:QUAT 2321 2371 -0.0218718 -3.11219 -0.0554362 0.0306878 -0.0030432 0.01424 0.999423 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.64 -0.0116889 -1.78222 399.713 -9.19335 100.27 +EDGE_SE3:QUAT 2322 2372 0.189236 -3.18682 -0.243921 0.0251185 -0.00223629 -0.0257199 0.999351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.75 -0.00247107 -0.729384 399.809 -7.54546 100.125 +EDGE_SE3:QUAT 2323 2373 -0.0731614 -3.02883 -0.174227 0.0352174 -0.00343979 0.00981768 0.999326 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.524 -0.0142675 -1.9253 399.623 -10.5517 100.372 +EDGE_SE3:QUAT 2324 2374 -0.00520651 -3.03417 -0.283874 0.0332545 -0.00376738 -0.016983 0.999296 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.569 -0.00905023 -1.54266 399.663 -9.98385 100.311 +EDGE_SE3:QUAT 2325 2375 -0.0228028 -3.07056 0.0573167 0.0317219 -0.0111704 0.0124946 0.999356 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.775 -0.0350369 -5.81996 399.647 -9.48098 100.379 +EDGE_SE3:QUAT 2326 2376 -0.0621299 -3.18296 -0.0424051 0.0288647 -0.00636943 -0.0461565 0.998497 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.692 -0.0126434 -2.37773 399.737 -8.71724 100.056 +EDGE_SE3:QUAT 2327 2377 0.0388514 -3.0083 -0.0987079 0.0309248 0.00147762 0.00865021 0.999483 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.619 0.00292881 0.577677 399.712 -9.27565 100.281 +EDGE_SE3:QUAT 2328 2378 -0.191664 -2.97448 0.0292238 0.0284615 -0.00408764 0.00287478 0.999582 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.699 -0.0119984 -2.09153 399.75 -8.53228 100.254 +EDGE_SE3:QUAT 2329 2379 0.131935 -3.08183 -0.113085 0.0272937 0.00643106 0.0250984 0.999292 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 0.0152549 2.80097 399.762 -8.21755 100.184 +EDGE_SE3:QUAT 2330 2380 -0.145342 -3.35581 -0.225241 0.034735 0.0140101 -0.00431199 0.999289 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.779 0.0484036 7.0922 399.559 -10.397 100.5 +EDGE_SE3:QUAT 2331 2381 -0.107607 -3.05488 0.0839114 0.0278514 0.00775635 0.00642304 0.999561 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.763 0.0212782 3.76874 399.744 -8.361 100.269 +EDGE_SE3:QUAT 2332 2382 0.321773 -3.06976 -0.253011 0.0393313 0.00205837 -0.0103683 0.99917 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.39 0.0111613 1.27223 399.534 -11.786 100.457 +EDGE_SE3:QUAT 2333 2383 0.0338217 -3.05433 -0.088552 0.0315336 -0.00177699 -0.0290918 0.999078 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.602 0.000163429 -0.336939 399.701 -9.46702 100.215 +EDGE_SE3:QUAT 2334 2384 -0.0264963 -3.03963 -0.00924977 0.0314817 -0.000720942 0.00803508 0.999472 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.605 -0.00384275 -0.511852 399.702 -9.43874 100.292 +EDGE_SE3:QUAT 2335 2385 -0.0202104 -3.26805 -0.192235 0.034487 0.00628006 0.0211675 0.999161 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.56 0.0177306 2.69785 399.629 -10.3665 100.334 +EDGE_SE3:QUAT 2336 2386 0.247688 -3.08574 0.0649253 0.0255882 0.000318565 -0.0180193 0.99951 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 0.0031511 0.435702 399.803 -7.6732 100.164 +EDGE_SE3:QUAT 2337 2387 -0.140196 -3.09267 -0.273355 0.0324959 -0.014357 -0.0124706 0.999291 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.824 -0.0485909 -6.93208 399.603 -9.77488 100.438 +EDGE_SE3:QUAT 2338 2388 0.0717771 -3.1169 -0.0473226 0.0219798 0.00585022 -0.00964141 0.999695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.856 0.0131542 3.05114 399.841 -6.58056 100.161 +EDGE_SE3:QUAT 2339 2389 0.0601862 -3.19448 0.0304527 0.0341812 0.00130412 0.0211609 0.999191 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.533 -0.00048642 0.217364 399.649 -10.2546 100.306 +EDGE_SE3:QUAT 2340 2390 -0.0178538 -3.13617 -0.0680685 0.0255408 -0.00819568 -0.0403683 0.998825 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.798 -0.0192659 -3.47171 399.781 -7.72708 100.07 +EDGE_SE3:QUAT 2341 2391 -0.0210466 -2.98952 -0.08232 0.0383827 0.00785513 0.0171053 0.999086 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.473 0.0266354 3.52815 399.535 -11.5323 100.45 +EDGE_SE3:QUAT 2342 2392 0.00965012 -3.27615 0.00561593 0.0304541 -0.00546591 0.0327809 0.998984 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.689 -0.0201851 -3.32723 399.707 -9.09679 100.199 +EDGE_SE3:QUAT 2343 2393 0.0676061 -3.09994 -0.179616 0.0290803 -0.0088034 -0.0236783 0.999258 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.741 -0.0243579 -3.98395 399.718 -8.76149 100.245 +EDGE_SE3:QUAT 2344 2394 -0.127267 -3.04509 -0.0207292 0.0238258 0.00249383 -0.0247698 0.999406 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 0.00830867 1.59961 399.827 -7.1339 100.115 +EDGE_SE3:QUAT 2345 2395 -0.10339 -3.05793 -0.190868 0.0235766 -0.00669803 -0.00996619 0.99965 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.83 -0.0154329 -3.20653 399.816 -7.08373 100.186 +EDGE_SE3:QUAT 2346 2396 -0.11939 -2.90669 -0.103871 0.032744 0.00642388 -0.0224965 0.99919 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 0.0237397 3.64989 399.66 -9.78858 100.306 +EDGE_SE3:QUAT 2347 2397 -0.0788292 -2.87156 0.05486 0.0293785 -0.000890402 0.00341875 0.999562 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.00319518 -0.505097 399.741 -8.80913 100.258 +EDGE_SE3:QUAT 2348 2398 -0.102262 -2.99928 0.0256153 0.0178225 -0.00379948 0.0145179 0.999729 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.895 -0.00725803 -2.05419 399.899 -5.33484 100.086 +EDGE_SE3:QUAT 2349 2399 0.120582 -3.00399 -0.121336 0.0318618 -0.00164731 0.0132337 0.999403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.00781846 -1.07568 399.694 -9.54949 100.29 +EDGE_SE3:QUAT 2350 2400 0.0257293 -3.17807 0.0465324 0.0266036 0.00432067 -0.00618232 0.999618 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.744 0.0121368 2.25771 399.78 -7.97256 100.222 +EDGE_SE3:QUAT 2351 2401 0.0806618 -3.17478 -0.0318378 0.0271157 -0.00632622 -0.00467452 0.999601 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.755 -0.0167875 -3.08532 399.764 -8.13687 100.245 +EDGE_SE3:QUAT 2352 2402 -0.0227351 -3.07862 -0.0456497 0.0212025 -0.00142116 -0.0449186 0.998765 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.82 0.00102166 -0.138039 399.865 -6.37424 99.9336 +EDGE_SE3:QUAT 2353 2403 0.114693 -3.13743 -0.309415 0.0391354 -0.00119045 0.0054216 0.999218 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.39 -0.0062847 -0.721633 399.54 -11.7303 100.458 +EDGE_SE3:QUAT 2354 2404 -0.110838 -3.05052 -0.151266 0.0268052 -0.000412072 -0.0224128 0.999389 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.713 0.00211501 0.154511 399.784 -8.04118 100.165 +EDGE_SE3:QUAT 2355 2405 -0.0313224 -3.13363 -0.133837 0.0291012 0.00209044 -0.0133661 0.999485 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 0.00818521 1.27759 399.744 -8.72121 100.24 +EDGE_SE3:QUAT 2356 2406 -0.0272206 -3.22467 0.0305596 0.0253941 -0.012234 -0.0274499 0.999226 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.906 -0.0341077 -5.6936 399.75 -7.68131 100.213 +EDGE_SE3:QUAT 2357 2407 -0.204509 -3.13282 -0.160111 0.0251231 -0.00487631 0.00475348 0.999661 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.781 -0.0126327 -2.50859 399.801 -7.52949 100.204 +EDGE_SE3:QUAT 2358 2408 0.114301 -3.04663 -0.0879111 0.0331046 -0.00405314 0.00402895 0.999436 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.585 -0.0141525 -2.10467 399.664 -9.92228 100.339 +EDGE_SE3:QUAT 2359 2409 0.116292 -3.14095 0.034373 0.0249696 -0.00309944 0.020964 0.999464 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.769 -0.00983769 -1.86231 399.808 -7.47585 100.152 +EDGE_SE3:QUAT 2360 2410 -0.16278 -2.95426 -0.0687947 0.0351376 0.000897148 -0.0076339 0.999353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.508 0.00500915 0.608929 399.629 -10.5335 100.365 +EDGE_SE3:QUAT 2361 2411 -0.11203 -3.06112 -0.203332 0.0414693 0.0023608 0.0218421 0.998898 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.313 0.00232034 0.634994 399.482 -12.4413 100.47 +EDGE_SE3:QUAT 2362 2412 -0.0174788 -3.11391 -0.134562 0.0301175 0.00251863 -0.00527017 0.999529 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.647 0.0084608 1.3535 399.725 -9.02837 100.274 +EDGE_SE3:QUAT 2363 2413 0.0925205 -3.04294 -0.123194 0.029455 0.00720614 0.0111506 0.999478 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.712 0.0202284 3.40336 399.72 -8.84788 100.281 +EDGE_SE3:QUAT 2364 2414 0.163078 -3.02221 -0.305698 0.0314954 0.00655815 0.00548113 0.999467 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 0.0199573 3.17294 399.686 -9.45019 100.323 +EDGE_SE3:QUAT 2365 2415 0.0898611 -3.11278 -0.230568 0.0356352 -0.0115075 -0.00488956 0.999287 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.656 -0.0409826 -5.64502 399.567 -10.6916 100.469 +EDGE_SE3:QUAT 2366 2416 0.178381 -3.07386 -0.0405802 0.034523 -0.00788239 0.00146356 0.999372 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.605 -0.0273959 -3.96815 399.617 -10.3468 100.401 +EDGE_SE3:QUAT 2367 2417 0.0435759 -2.9972 -0.241973 0.0187931 -0.000569496 -0.0206444 0.99961 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.859 0.000388157 -0.0518246 399.894 -5.6397 100.063 +EDGE_SE3:QUAT 2368 2418 0.0265457 -3.18037 -0.149991 0.036395 -0.00686753 0.00580611 0.999297 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 -0.0259885 -3.55695 399.583 -10.902 100.429 +EDGE_SE3:QUAT 2369 2419 0.0404429 -3.25006 0.166059 0.0286259 0.00668476 0.00107812 0.999567 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.729 0.0190454 3.32191 399.736 -8.58474 100.277 +EDGE_SE3:QUAT 2370 2420 -0.037574 -2.96721 0.111019 0.0229611 0.00220231 -0.00096421 0.999733 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.796 0.00514541 1.11393 399.84 -6.886 100.162 +EDGE_SE3:QUAT 2371 2421 -0.138485 -3.11691 -0.175378 0.0259153 0.00325777 0.0169671 0.999515 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.74 0.00638847 1.36376 399.795 -7.78326 100.179 +EDGE_SE3:QUAT 2372 2422 0.0084985 -3.18732 0.0652056 0.024811 -0.005172 -0.0033351 0.999673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.787 -0.0125731 -2.53513 399.805 -7.44398 100.202 +EDGE_SE3:QUAT 2373 2423 -0.00079279 -3.12264 -0.0881471 0.0314283 -0.00219183 -0.0516795 0.998167 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.604 0.00333235 -0.118974 399.702 -9.45071 100.03 +EDGE_SE3:QUAT 2374 2424 -0.0621977 -2.90502 -0.0614072 0.0383019 -0.0011015 0.0206574 0.999052 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.419 -0.0101202 -1.02426 399.559 -11.4783 100.4 +EDGE_SE3:QUAT 2375 2425 0.0112092 -2.88165 -0.0909757 0.0294337 0.00416984 0.000440987 0.999558 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 0.0121974 2.07563 399.733 -8.82627 100.272 +EDGE_SE3:QUAT 2376 2426 0.0210469 -3.00441 -0.169417 0.0334299 -0.006416 0.0116152 0.999353 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.616 -0.0230576 -3.43787 399.647 -10.0075 100.354 +EDGE_SE3:QUAT 2377 2427 -0.0539781 -3.20024 -0.219876 0.0345342 0.00492663 0.00296183 0.999387 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.553 0.016405 2.3995 399.633 -10.3564 100.373 +EDGE_SE3:QUAT 2378 2428 0.0936004 -2.91381 -0.0953071 0.0251213 -0.00749107 0.0123865 0.99958 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.829 -0.0190357 -3.93043 399.787 -7.51452 100.216 +EDGE_SE3:QUAT 2379 2429 0.113707 -3.0694 -0.167609 0.0227233 -0.00166316 -0.0193251 0.999554 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.795 -0.0018278 -0.567515 399.844 -6.82205 100.119 +EDGE_SE3:QUAT 2380 2430 0.0881312 -3.06934 -0.113937 0.0219571 -0.00135294 -0.00952472 0.999713 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 -0.0020712 -0.550667 399.855 -6.58821 100.137 +EDGE_SE3:QUAT 2381 2431 -0.00909279 -3.01789 0.0443456 0.0280148 0.00349792 -0.011054 0.99954 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.706 0.0112312 1.93339 399.759 -8.39327 100.233 +EDGE_SE3:QUAT 2382 2432 0.014111 -3.10677 -0.182714 0.0350023 -0.000893154 -0.00275735 0.999383 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.511 -0.00244648 -0.388198 399.632 -10.4948 100.367 +EDGE_SE3:QUAT 2383 2433 -0.119578 -3.14035 -0.0274269 0.029122 -0.00575383 0.0287494 0.999146 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.722 -0.0193307 -3.37527 399.73 -8.70005 100.201 +EDGE_SE3:QUAT 2384 2434 -0.000125601 -3.02959 -0.122347 0.0275798 0.0046812 0.0413038 0.998755 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.708 0.00747028 1.6525 399.765 -8.31163 100.068 +EDGE_SE3:QUAT 2385 2435 -0.145537 -2.97413 -0.0529797 0.0305846 -0.00176458 -0.00514109 0.999517 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.629 -0.00444923 -0.787218 399.718 -9.17288 100.28 +EDGE_SE3:QUAT 2386 2436 0.0710403 -3.06771 -0.133144 0.0283094 0.000457995 0.00789952 0.999568 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.679 2.93916e-05 0.0946797 399.76 -8.49024 100.234 +EDGE_SE3:QUAT 2387 2437 0.137827 -3.10741 -0.174667 0.0347578 0.0104643 0.0125764 0.999262 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.643 0.0356272 4.96515 399.596 -10.445 100.418 +EDGE_SE3:QUAT 2388 2438 0.0449994 -3.20431 -0.233903 0.0266742 0.00820317 -0.0175224 0.999457 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.817 0.0220136 4.37943 399.758 -7.96959 100.235 +EDGE_SE3:QUAT 2389 2439 0.173802 -3.16614 -0.112143 0.0256725 0.00173097 0.00668124 0.999647 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.739 0.00358642 0.762053 399.801 -7.70155 100.195 +EDGE_SE3:QUAT 2390 2440 -0.0254123 -3.1022 0.00522851 0.0250625 -0.00318378 -0.010607 0.999625 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.759 -0.00679851 -1.4314 399.808 -7.52313 100.183 +EDGE_SE3:QUAT 2391 2441 0.0127781 -3.09094 -0.0970962 0.035342 -0.00324405 0.0446387 0.998373 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.537 -0.0206119 -2.56316 399.618 -10.5698 100.191 +EDGE_SE3:QUAT 2392 2442 -0.0676438 -2.86307 -0.226622 0.03792 0.00864963 0.000572585 0.999243 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.521 0.0327092 4.30731 399.539 -11.3667 100.483 +EDGE_SE3:QUAT 2393 2443 -0.039984 -3.169 -0.0995151 0.0318121 0.00371845 0.0506276 0.998204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.597 0.00188366 0.888038 399.692 -9.5805 100.052 +EDGE_SE3:QUAT 2394 2444 0.0530277 -3.12004 -0.0117816 0.033575 -0.00845902 -0.045095 0.998382 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.6 -0.0219079 -3.31031 399.638 -10.1454 100.171 +EDGE_SE3:QUAT 2395 2445 0.0149223 -3.10563 -0.203804 0.0332421 -0.00103841 -0.0112457 0.999384 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.558 -0.000967928 -0.294423 399.668 -9.96966 100.319 +EDGE_SE3:QUAT 2396 2446 -0.0632931 -3.0343 -0.226887 0.0213015 -0.00257875 -0.009504 0.999725 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.825 -0.00472154 -1.16732 399.861 -6.39391 100.131 +EDGE_SE3:QUAT 2397 2447 -0.0809943 -2.97586 -0.213127 0.0297102 0.0016658 0.0190084 0.999376 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.648 0.00162229 0.49326 399.734 -8.91597 100.23 +EDGE_SE3:QUAT 2398 2448 -0.100975 -2.97909 -0.20848 0.0225927 -0.00986575 -0.00156106 0.999695 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.921 -0.0224599 -4.91109 399.808 -6.77751 100.221 +EDGE_SE3:QUAT 2399 2449 -0.0570497 -3.04541 0.0151781 0.036651 -0.00376116 0.0135082 0.99923 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.488 -0.0169352 -2.17506 399.591 -10.9776 100.397 +EDGE_SE3:QUAT 2400 2450 0.0569956 -3.06219 -0.0730208 0.0258004 0.00533616 0.0418692 0.998776 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 0.00946081 2.01471 399.791 -7.78421 100.038 +EDGE_SE3:QUAT 2401 2451 0.0233072 -3.05722 0.0254617 0.0324612 -0.00221816 0.00509458 0.999458 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.586 -0.00820722 -1.20722 399.682 -9.73086 100.317 +EDGE_SE3:QUAT 2402 2452 -0.0381196 -2.9876 -0.252388 0.0333064 0.00453789 -0.000561517 0.999435 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.583 0.015196 2.27806 399.659 -9.98534 100.347 +EDGE_SE3:QUAT 2403 2453 -0.123723 -2.91757 -0.152678 0.0253412 -0.00734468 -0.00437264 0.999642 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.81 -0.0184733 -3.60433 399.786 -7.60536 100.227 +EDGE_SE3:QUAT 2404 2454 -0.00800361 -3.05468 -0.162409 0.0356536 -0.000807656 0.00335258 0.999358 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.493 -0.00371886 -0.475052 399.618 -10.6887 100.381 +EDGE_SE3:QUAT 2405 2455 0.0894775 -3.09437 -0.22297 0.0273416 0.00852198 0.0130051 0.999505 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.785 0.0229215 4.04506 399.748 -8.22044 100.255 +EDGE_SE3:QUAT 2406 2456 0.0240355 -2.96653 -0.258981 0.0377127 0.00320654 0.0163207 0.99915 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.438 0.00760707 1.23176 399.57 -11.3165 100.405 +EDGE_SE3:QUAT 2407 2457 0.11967 -2.95021 -0.0981865 0.0278504 0.000336112 0.0285833 0.999203 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 -0.0034845 -0.309567 399.767 -8.35493 100.151 +EDGE_SE3:QUAT 2408 2458 -0.0141258 -3.0485 -0.0227253 0.0365716 0.00642555 0.0028168 0.999306 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.516 0.0229198 3.14753 399.583 -10.9667 100.429 +EDGE_SE3:QUAT 2409 2459 -0.14116 -3.12543 -0.148791 0.0338061 -0.0100042 -0.00468595 0.999367 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.667 -0.0336077 -4.90346 399.618 -10.143 100.409 +EDGE_SE3:QUAT 2410 2460 0.10304 -3.05122 -0.131541 0.0311792 -0.010913 -0.0113387 0.99939 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.752 -0.0341493 -5.24094 399.662 -9.37154 100.357 +EDGE_SE3:QUAT 2411 2461 -0.0251865 -3.15388 0.0557313 0.026525 0.00564407 0.0226684 0.999375 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.748 0.0127807 2.45849 399.777 -7.98047 100.178 +EDGE_SE3:QUAT 2412 2462 0.078235 -2.91957 -0.14201 0.039906 -0.000787987 -0.00835521 0.999168 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.363 -0.000478032 -0.193461 399.522 -11.9637 100.471 +EDGE_SE3:QUAT 2413 2463 0.0262409 -2.93312 -0.106771 0.0214056 0.00245805 -0.0137419 0.999673 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.827 0.00632603 1.40481 399.86 -6.41353 100.124 +EDGE_SE3:QUAT 2414 2464 -0.0625469 -3.04769 0.102979 0.030117 -0.00421756 0.024476 0.999238 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.672 -0.0160179 -2.54826 399.719 -9.0107 100.229 +EDGE_SE3:QUAT 2415 2465 0.076364 -3.12365 -0.176031 0.0284956 -0.00160078 -0.0158042 0.999468 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.676 -0.00202266 -0.529509 399.756 -8.55061 100.22 +EDGE_SE3:QUAT 2416 2466 0.158965 -3.13729 -0.0695265 0.032759 -0.0113467 -0.0533962 0.997971 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 -0.0341572 -4.60611 399.634 -9.94627 100.105 +EDGE_SE3:QUAT 2417 2467 0.0951203 -3.09252 -0.211451 0.0321765 -0.00781515 -0.0197669 0.999256 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.648 -0.0228399 -3.52165 399.667 -9.67824 100.309 +EDGE_SE3:QUAT 2418 2468 -0.0938255 -3.05576 -0.0404847 0.0290836 0.000400296 -0.0107358 0.999519 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.663 0.00296705 0.387258 399.746 -8.72069 100.243 +EDGE_SE3:QUAT 2419 2469 -0.106433 -3.00595 -0.0774184 0.0272593 -0.000398806 -0.0201278 0.999426 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.703 0.00190379 0.12988 399.777 -8.17691 100.182 +EDGE_SE3:QUAT 2420 2470 -0.0431197 -3.14662 -0.145837 0.023845 0.00346974 -0.0264568 0.99936 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.797 0.0104528 2.11141 399.824 -7.13362 100.112 +EDGE_SE3:QUAT 2421 2471 0.0797938 -2.99855 -0.00896016 0.0325347 0.00338419 -0.00692344 0.999441 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.594 0.0122936 1.82561 399.678 -9.7503 100.322 +EDGE_SE3:QUAT 2422 2472 -0.0744363 -3.11552 0.0459824 0.0302713 0.00961129 0.0197876 0.9993 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.733 0.0283426 4.44185 399.69 -9.11401 100.294 +EDGE_SE3:QUAT 2423 2473 -0.290219 -2.87447 -0.0431851 0.0199679 0.010513 0.00615897 0.999726 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.979 0.0217626 5.18257 399.837 -6.00054 100.192 +EDGE_SE3:QUAT 2424 2474 -0.0905849 -3.13565 -0.19316 0.0280725 0.00295932 0.0252899 0.999282 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.69 0.00452336 1.052 399.761 -8.43421 100.176 +EDGE_SE3:QUAT 2425 2475 0.113845 -2.91556 -0.0731655 0.0362553 -0.00123522 -0.0122867 0.999266 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.475 -0.00125046 -0.34965 399.605 -10.8727 100.38 +EDGE_SE3:QUAT 2426 2476 -0.0107406 -3.03889 -0.169288 0.0249108 -0.00285149 -0.00944615 0.999641 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.76 -0.00603797 -1.28371 399.811 -7.47629 100.182 +EDGE_SE3:QUAT 2427 2477 -0.259508 -3.04391 0.148407 0.0366343 0.00382163 -0.0126641 0.999241 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.489 0.0169434 2.18662 399.591 -10.973 100.399 +EDGE_SE3:QUAT 2428 2478 0.109832 -2.87685 -0.274584 0.0388864 0.00703733 0.0123855 0.999142 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.448 0.02452 3.22499 399.528 -11.6736 100.469 +EDGE_SE3:QUAT 2429 2479 0.0363237 -3.15614 -0.0869768 0.0302179 0.0106569 0.0258446 0.999152 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.753 0.031979 4.85391 399.684 -9.1151 100.277 +EDGE_SE3:QUAT 2430 2480 0.097677 -3.18419 0.0924348 0.0362284 -0.00412263 -0.00585921 0.999318 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.494 -0.0135264 -1.93161 399.6 -10.8659 100.401 +EDGE_SE3:QUAT 2431 2481 -0.0306665 -3.09426 -0.190765 0.0249844 -0.00283049 0.0340044 0.999105 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.771 -0.0104449 -1.92255 399.808 -7.47488 100.081 +EDGE_SE3:QUAT 2432 2482 0.0722814 -2.84839 -0.162707 0.0260155 -0.00880333 -0.0228431 0.999362 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.812 -0.0225541 -4.04131 399.768 -7.8416 100.199 +EDGE_SE3:QUAT 2433 2483 -0.0290034 -2.91556 -0.125121 0.0313917 -0.00678321 0.0028908 0.99948 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.668 -0.0216138 -3.44359 399.686 -9.40786 100.328 +EDGE_SE3:QUAT 2434 2484 -0.0834858 -3.13496 -0.155794 0.031809 0.00224616 -0.0232411 0.999221 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.609 0.0114432 1.56491 399.694 -9.52805 100.255 +EDGE_SE3:QUAT 2435 2485 -0.0846365 -3.10733 -0.151788 0.0316013 0.000163809 0.0101059 0.999449 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.601 -0.00150028 -0.109723 399.7 -9.47615 100.289 +EDGE_SE3:QUAT 2436 2486 0.0439303 -3.04648 -0.0140596 0.0374654 0.00267739 0.0141836 0.999194 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.443 0.00613542 1.0181 399.576 -11.2396 100.405 +EDGE_SE3:QUAT 2437 2487 0.101117 -2.90752 -0.24059 0.0313301 0.00714999 0.00367147 0.999477 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.671 0.0220031 3.50338 399.685 -9.39852 100.328 +EDGE_SE3:QUAT 2438 2488 0.0335922 -2.95863 -0.126668 0.0440604 -0.00582003 -0.0469917 0.997906 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.232 -0.00833556 -1.65856 399.407 -13.2645 100.374 +EDGE_SE3:QUAT 2439 2489 -0.0502104 -2.91591 0.130835 0.0330194 -0.00392293 -0.0188795 0.999269 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.576 -0.00916741 -1.5851 399.668 -9.91555 100.3 +EDGE_SE3:QUAT 2440 2490 0.0375954 -3.02576 -0.0402119 0.0360921 0.00357918 -0.0234423 0.999067 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.508 0.0181426 2.29415 399.603 -10.8042 100.349 +EDGE_SE3:QUAT 2441 2491 0.0977798 -3.22841 -0.0112792 0.0399439 0.00407953 -0.0152497 0.999077 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.393 0.0205031 2.40189 399.514 -11.961 100.47 +EDGE_SE3:QUAT 2442 2492 -0.0458312 -2.91145 0.0499288 0.0328478 0.00978448 0.0200082 0.999212 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.67 0.0307923 4.49271 399.641 -9.88678 100.343 +EDGE_SE3:QUAT 2443 2493 0.130498 -3.03704 -0.0405533 0.0313275 0.00189175 0.0413039 0.998654 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.607 -0.00218189 0.167912 399.704 -9.41194 100.125 +EDGE_SE3:QUAT 2444 2494 -0.00111674 -2.87381 -0.032075 0.0343359 0.00364538 -0.0222047 0.999157 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.557 0.0169283 2.27734 399.64 -10.2788 100.317 +EDGE_SE3:QUAT 2445 2495 -0.0223247 -3.03891 -0.157711 0.0300186 -0.0119597 -0.0122631 0.999403 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.809 -0.0367444 -5.75595 399.674 -9.02801 100.35 +EDGE_SE3:QUAT 2446 2496 0.073903 -3.10015 -0.0759222 0.0301331 0.00461855 0.0192122 0.999351 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.655 0.0109561 1.9595 399.72 -9.05375 100.247 +EDGE_SE3:QUAT 2447 2497 -0.095026 -3.19391 -0.103208 0.0393828 -0.00616679 -0.00160047 0.999204 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.427 -0.0238558 -3.04167 399.52 -11.8066 100.491 +EDGE_SE3:QUAT 2448 2498 -0.234395 -3.01476 0.126794 0.0299929 0.0010653 -0.02447 0.99925 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.646 0.00743673 0.972085 399.729 -8.98942 100.212 +EDGE_SE3:QUAT 2449 2499 -0.110695 -3.08307 -0.11704 0.0336013 0.00120318 0.0052361 0.999421 10 0 0 0 0 0 10 0 0 0 0 10 0 0 0 399.55 0.00286168 0.495442 399.661 -10.076 100.337 diff --git a/examples/g2o.rs b/examples/g2o.rs index cdcf319..e66103b 100644 --- a/examples/g2o.rs +++ b/examples/g2o.rs @@ -18,7 +18,7 @@ use std::net::{SocketAddr, SocketAddrV4}; #[cfg(feature = "rerun")] fn rerun_init(opt: &mut GaussNewton, dim: &str, obj: &str) { // Setup the rerun & the callback - let socket = SocketAddrV4::new("172.31.65.81".parse().unwrap(), 9876); + let socket = SocketAddrV4::new("0.0.0.0".parse().unwrap(), 9876); let rec = rerun::RecordingStreamBuilder::new("rerun_example_dna_abacus") .connect_tcp_opts(SocketAddr::V4(socket), rerun::default_flush_timeout()) .unwrap();