From f32a8229433164815cc75584a626b3207f6136fd Mon Sep 17 00:00:00 2001 From: Jiangtao Hu Date: Tue, 15 Aug 2017 23:36:08 -0700 Subject: [PATCH] planning: move speed/path debug info into optimizer and fix unit test. --- modules/planning/optimizer/path_optimizer.cc | 18 +- modules/planning/optimizer/path_optimizer.h | 2 + modules/planning/optimizer/speed_optimizer.cc | 13 +- modules/planning/optimizer/speed_optimizer.h | 2 + modules/planning/planner/em/em_planner.cc | 18 +- modules/planning/planner/em/em_planner.h | 1 - .../qp_spline_path/42_apollo_planning.pb.txt | 12019 ++-------------- 7 files changed, 1052 insertions(+), 11021 deletions(-) diff --git a/modules/planning/optimizer/path_optimizer.cc b/modules/planning/optimizer/path_optimizer.cc index ae17239671..ca609eb6dd 100644 --- a/modules/planning/optimizer/path_optimizer.cc +++ b/modules/planning/optimizer/path_optimizer.cc @@ -28,9 +28,21 @@ PathOptimizer::PathOptimizer(const std::string& name) : Optimizer(name) {} apollo::common::Status PathOptimizer::Optimize(Frame* frame) { frame_ = frame; auto* planning_data = frame->mutable_planning_data(); - return Process(planning_data->speed_data(), frame->reference_line(), - frame->PlanningStartPoint(), frame->path_decision(), - planning_data->mutable_path_data()); + auto ret = Process(planning_data->speed_data(), frame->reference_line(), + frame->PlanningStartPoint(), frame->path_decision(), + planning_data->mutable_path_data()); + RecordDebugInfo(planning_data->path_data()); + + return ret; +} + +void PathOptimizer::RecordDebugInfo(const PathData& path_data) { + auto debug = frame_->MutableADCTrajectory()->mutable_debug(); + const auto& path_points = path_data.discretized_path().path_points(); + auto ptr_optimized_path = debug->mutable_planning_data()->add_path(); + ptr_optimized_path->set_name(name()); + ptr_optimized_path->mutable_path_point()->CopyFrom( + {path_points.begin(), path_points.end()}); } } // namespace planning diff --git a/modules/planning/optimizer/path_optimizer.h b/modules/planning/optimizer/path_optimizer.h index b7acaae689..1285bc20c4 100644 --- a/modules/planning/optimizer/path_optimizer.h +++ b/modules/planning/optimizer/path_optimizer.h @@ -45,6 +45,8 @@ class PathOptimizer : public Optimizer { const SpeedData &speed_data, const ReferenceLine &reference_line, const common::TrajectoryPoint &init_point, PathDecision *const path_decision, PathData *const path_data) = 0; + + void RecordDebugInfo(const PathData &path_data); }; } // namespace planning diff --git a/modules/planning/optimizer/speed_optimizer.cc b/modules/planning/optimizer/speed_optimizer.cc index 04ccb5a422..25371caf1e 100644 --- a/modules/planning/optimizer/speed_optimizer.cc +++ b/modules/planning/optimizer/speed_optimizer.cc @@ -32,9 +32,20 @@ SpeedOptimizer::SpeedOptimizer(const std::string& name) : Optimizer(name) {} apollo::common::Status SpeedOptimizer::Optimize(Frame* frame) { frame_ = frame; auto* planning_data = frame->mutable_planning_data(); - return Process(planning_data->path_data(), frame->PlanningStartPoint(), + auto ret = Process(planning_data->path_data(), frame->PlanningStartPoint(), frame->reference_line(), frame->path_decision(), planning_data->mutable_speed_data()); + RecordDebugInfo(planning_data->speed_data()); + return ret; +} + +void SpeedOptimizer::RecordDebugInfo(const SpeedData& speed_data) { + auto debug = frame_->MutableADCTrajectory()->mutable_debug(); + auto ptr_speed_plan = debug->mutable_planning_data()->add_speed_plan(); + ptr_speed_plan->set_name(name()); + ptr_speed_plan->mutable_speed_point()->CopyFrom( + {speed_data.speed_vector().begin(), + speed_data.speed_vector().end()}); } void SpeedOptimizer::RecordSTGraphDebug( diff --git a/modules/planning/optimizer/speed_optimizer.h b/modules/planning/optimizer/speed_optimizer.h index 03999ab2e6..324464473b 100644 --- a/modules/planning/optimizer/speed_optimizer.h +++ b/modules/planning/optimizer/speed_optimizer.h @@ -49,6 +49,8 @@ class SpeedOptimizer : public Optimizer { void RecordSTGraphDebug(const std::vector& boundaries, const SpeedLimit& speed_limits, const SpeedData& speed_data); + void RecordDebugInfo(const SpeedData& speed_data); + }; } // namespace planning diff --git a/modules/planning/planner/em/em_planner.cc b/modules/planning/planner/em/em_planner.cc index 1c95b5bcb6..8a834a7f14 100644 --- a/modules/planning/planner/em/em_planner.cc +++ b/modules/planning/planner/em/em_planner.cc @@ -87,7 +87,6 @@ Status EMPlanner::Init(const PlanningConfig& config) { } void EMPlanner::RecordDebugInfo(const std::string& name, - const PlanningData* planning_data, const double time_diff_ms, planning_internal::Debug* ptr_debug, planning::LatencyStats* ptr_latency_stats) { @@ -97,21 +96,6 @@ void EMPlanner::RecordDebugInfo(const std::string& name, } OptimizerType type; DCHECK(OptimizerType_Parse(name, &type)); - if (type == DP_POLY_PATH_OPTIMIZER || type == QP_SPLINE_PATH_OPTIMIZER) { - const auto& path_points = - planning_data->path_data().discretized_path().path_points(); - auto ptr_optimized_path = ptr_debug->mutable_planning_data()->add_path(); - ptr_optimized_path->set_name(name); - ptr_optimized_path->mutable_path_point()->CopyFrom( - {path_points.begin(), path_points.end()}); - } else if (type == DP_ST_SPEED_OPTIMIZER || - type == QP_SPLINE_ST_SPEED_OPTIMIZER) { - const auto& speed_points = planning_data->speed_data().speed_vector(); - auto ptr_speed_plan = ptr_debug->mutable_planning_data()->add_speed_plan(); - ptr_speed_plan->set_name(name); - ptr_speed_plan->mutable_speed_point()->CopyFrom( - {speed_points.begin(), speed_points.end()}); - } auto ptr_stats = ptr_latency_stats->add_processor_stats(); ptr_stats->set_name(name); @@ -151,7 +135,7 @@ Status EMPlanner::Plan(const TrajectoryPoint& planning_start_point, if (FLAGS_enable_record_debug && ptr_debug != nullptr && ptr_latency_stats != nullptr) { - RecordDebugInfo(optimizer->name(), planning_data, time_diff_ms, ptr_debug, + RecordDebugInfo(optimizer->name(), time_diff_ms, ptr_debug, ptr_latency_stats); } } diff --git a/modules/planning/planner/em/em_planner.h b/modules/planning/planner/em/em_planner.h index 6d46463bed..12aa92cee3 100644 --- a/modules/planning/planner/em/em_planner.h +++ b/modules/planning/planner/em/em_planner.h @@ -77,7 +77,6 @@ class EMPlanner : public Planner { void PopulateDecision(Frame* frame); void RecordDebugInfo(const std::string& name, - const PlanningData* planning_data, const double time_diff_ms, planning_internal::Debug* ptr_debug, planning::LatencyStats* ptr_latency_stats); diff --git a/modules/planning/testdata/qp_spline_path/42_apollo_planning.pb.txt b/modules/planning/testdata/qp_spline_path/42_apollo_planning.pb.txt index 2d2f7f7690..88487472d0 100644 --- a/modules/planning/testdata/qp_spline_path/42_apollo_planning.pb.txt +++ b/modules/planning/testdata/qp_spline_path/42_apollo_planning.pb.txt @@ -6,10994 +6,1015 @@ header { debug { planning_data { path { - name: "DP_POLY_PATH_OPTIMIZER" + name: "QP_SPLINE_PATH_OPTIMIZER" path_point { - x: 586347.749164 + x: 586347.749165 y: 4140711.30439 - z: 0.0 - theta: 1.30459532321 - kappa: 2.88760808843e-05 - s: 0.0 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.775471 - y: 4140711.40087 - z: 0.0 - theta: 1.30460808992 - kappa: 0.000224032377474 - s: 0.100000000195 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.801775 - y: 4140711.49734 - z: 0.0 - theta: 1.30463962804 - kappa: 0.000404377866869 - s: 0.20000000013 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.828076 - y: 4140711.59382 - z: 0.0 - theta: 1.30468848779 - kappa: 0.000570280845833 - s: 0.30000165367 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.854371 - y: 4140711.69031 - z: 0.0 - theta: 1.30475321597 - kappa: 0.000722139918142 - s: 0.400001654084 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.880659 - y: 4140711.78679 - z: 0.0 - theta: 1.30483245602 - kappa: 0.000860311624525 - s: 0.500001654682 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.906938 - y: 4140711.88327 - z: 0.0 - theta: 1.30492484172 - kappa: 0.000985185752565 - s: 0.600001657384 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.933208 - y: 4140711.97976 - z: 0.0 - theta: 1.30502905535 - kappa: 0.00109715060953 - s: 0.700001662714 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.959468 - y: 4140712.07625 - z: 0.0 - theta: 1.30514385235 - kappa: 0.00119655185959 - s: 0.800001672149 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.985716 - y: 4140712.17275 - z: 0.0 - theta: 1.30526796757 - kappa: 0.00128380116619 - s: 0.900001687418 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.011951 - y: 4140712.26924 - z: 0.0 - theta: 1.30540021632 - kappa: 0.00135926409057 - s: 1.00000171082 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.038174 - y: 4140712.36574 - z: 0.0 - theta: 1.30553944147 - kappa: 0.00142330884223 - s: 1.100001744 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.064383 - y: 4140712.46225 - z: 0.0 - theta: 1.30568451112 - kappa: 0.0014763373615 - s: 1.20000179047 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.090577 - y: 4140712.55876 - z: 0.0 - theta: 1.30583435228 - kappa: 0.00151870061536 - s: 1.30000185155 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.116757 - y: 4140712.65527 - z: 0.0 - theta: 1.30598791106 - kappa: 0.00155079296423 - s: 1.40000193115 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.142922 - y: 4140712.75179 - z: 0.0 - theta: 1.30614418148 - kappa: 0.00157300246861 - s: 1.50000203106 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.169072 - y: 4140712.84831 - z: 0.0 - theta: 1.30630219283 - kappa: 0.00158567080913 - s: 1.60000215473 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.195206 - y: 4140712.94483 - z: 0.0 - theta: 1.30646101208 - kappa: 0.00158921499526 - s: 1.70000230454 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.221325 - y: 4140713.04136 - z: 0.0 - theta: 1.30661974567 - kappa: 0.00158399701838 - s: 1.80000248291 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.247429 - y: 4140713.13789 - z: 0.0 - theta: 1.30677753088 - kappa: 0.00157038574842 - s: 1.90000269296 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.273518 - y: 4140713.23443 - z: 0.0 - theta: 1.30693355891 - kappa: 0.00154878615954 - s: 2.00000293596 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.299592 - y: 4140713.33097 - z: 0.0 - theta: 1.30708703487 - kappa: 0.00151954333062 - s: 2.10000321451 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.325651 - y: 4140713.42752 - z: 0.0 - theta: 1.30723722282 - kappa: 0.00148305690861 - s: 2.20000353006 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.351696 - y: 4140713.52407 - z: 0.0 - theta: 1.3073834264 - kappa: 0.00143971401747 - s: 2.30000388341 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.377727 - y: 4140713.62062 - z: 0.0 - theta: 1.30752494749 - kappa: 0.00138985303954 - s: 2.40000427665 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.403744 - y: 4140713.71717 - z: 0.0 - theta: 1.30766118852 - kappa: 0.00133389596022 - s: 2.50000470947 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.429749 - y: 4140713.81373 - z: 0.0 - theta: 1.30779154307 - kappa: 0.00127220081862 - s: 2.600005183 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.455741 - y: 4140713.9103 - z: 0.0 - theta: 1.30791544546 - kappa: 0.00120513779492 - s: 2.70000569602 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.481722 - y: 4140714.00686 - z: 0.0 - theta: 1.30803241135 - kappa: 0.00113311449647 - s: 2.80000624791 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.507692 - y: 4140714.10343 - z: 0.0 - theta: 1.30814191814 - kappa: 0.00105646970709 - s: 2.900006839 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.533652 - y: 4140714.20001 - z: 0.0 - theta: 1.3082435542 - kappa: 0.000975608992919 - s: 3.00000746636 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.559602 - y: 4140714.29658 - z: 0.0 - theta: 1.30833692979 - kappa: 0.000890917782077 - s: 3.10000812869 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.585544 - y: 4140714.39316 - z: 0.0 - theta: 1.30842162055 - kappa: 0.000802766313323 - s: 3.20000882446 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.611478 - y: 4140714.48974 - z: 0.0 - theta: 1.30849737046 - kappa: 0.000711584181602 - s: 3.30000954999 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.637405 - y: 4140714.58632 - z: 0.0 - theta: 1.30856386066 - kappa: 0.000617758717663 - s: 3.40001135842 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.663326 - y: 4140714.6829 - z: 0.0 - theta: 1.3086208394 - kappa: 0.000521670757485 - s: 3.50001209832 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.689242 - y: 4140714.77949 - z: 0.0 - theta: 1.30866813944 - kappa: 0.000423694129628 - s: 3.60001285786 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.715154 - y: 4140714.87607 - z: 0.0 - theta: 1.30870553274 - kappa: 0.000324215249861 - s: 3.70001363487 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.741063 - y: 4140714.97266 - z: 0.0 - theta: 1.30873293111 - kappa: 0.000223607538041 - s: 3.80001442397 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.76697 - y: 4140715.06925 - z: 0.0 - theta: 1.30875024469 - kappa: 0.000122249323454 - s: 3.90001522217 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.792875 - y: 4140715.16583 - z: 0.0 - theta: 1.30875736686 - kappa: 2.05263222851e-05 - s: 4.00001602605 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.81878 - y: 4140715.26242 - z: 0.0 - theta: 1.30875434003 - kappa: -8.11905636795e-05 - s: 4.10001682969 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.844686 - y: 4140715.35901 - z: 0.0 - theta: 1.30874115044 - kappa: -0.000182517917312 - s: 4.20001763047 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.870594 - y: 4140715.45559 - z: 0.0 - theta: 1.30871785382 - kappa: -0.000283076415335 - s: 4.30001842424 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.896505 - y: 4140715.55218 - z: 0.0 - theta: 1.30868458019 - kappa: -0.000382491926558 - s: 4.40001920651 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.922419 - y: 4140715.64876 - z: 0.0 - theta: 1.30864140892 - kappa: -0.000480377894096 - s: 4.50001997372 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.948338 - y: 4140715.74535 - z: 0.0 - theta: 1.30858855402 - kappa: -0.00057636130922 - s: 4.60002072225 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.974263 - y: 4140715.84193 - z: 0.0 - theta: 1.30852622493 - kappa: -0.000670063332014 - s: 4.70002144807 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.000194 - y: 4140715.93851 - z: 0.0 - theta: 1.30845462693 - kappa: -0.000761098804476 - s: 4.80002214973 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.026132 - y: 4140716.03509 - z: 0.0 - theta: 1.30837409752 - kappa: -0.000849096443475 - s: 4.90002282241 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.052078 - y: 4140716.13166 - z: 0.0 - theta: 1.30828492806 - kappa: -0.000933672613933 - s: 5.0000234645 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.078034 - y: 4140716.22824 - z: 0.0 - theta: 1.30818748099 - kappa: -0.00101444844235 - s: 5.10002407376 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.103999 - y: 4140716.32481 - z: 0.0 - theta: 1.30808218405 - kappa: -0.00109104944296 - s: 5.20002464768 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.129975 - y: 4140716.42138 - z: 0.0 - theta: 1.30796942433 - kappa: -0.00116308887126 - s: 5.30002518604 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.155962 - y: 4140716.51794 - z: 0.0 - theta: 1.30784971737 - kappa: -0.0012301940695 - s: 5.40002568632 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.181961 - y: 4140716.6145 - z: 0.0 - theta: 1.30772357266 - kappa: -0.00129198566101 - s: 5.50002614836 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.207972 - y: 4140716.71106 - z: 0.0 - theta: 1.30759150661 - kappa: -0.0013480790028 - s: 5.6000265721 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.233996 - y: 4140716.80762 - z: 0.0 - theta: 1.30745415225 - kappa: -0.00139810241607 - s: 5.70002695763 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.260034 - y: 4140716.90417 - z: 0.0 - theta: 1.30731210649 - kappa: -0.00144167204426 - s: 5.8000273057 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.286086 - y: 4140717.00071 - z: 0.0 - theta: 1.30716603768 - kappa: -0.00147840945115 - s: 5.90002761605 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.312152 - y: 4140717.09726 - z: 0.0 - theta: 1.30701667176 - kappa: -0.00150793981424 - s: 6.00002789064 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.338232 - y: 4140717.1938 - z: 0.0 - theta: 1.30686470388 - kappa: -0.00152987623016 - s: 6.10002813213 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.364328 - y: 4140717.29033 - z: 0.0 - theta: 1.30671095039 - kappa: -0.00154384641113 - s: 6.20002834024 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.390438 - y: 4140717.38686 - z: 0.0 - theta: 1.30655622166 - kappa: -0.00154947049819 - s: 6.30002851801 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.416563 - y: 4140717.48339 - z: 0.0 - theta: 1.30640134437 - kappa: -0.00154636440001 - s: 6.40002866849 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.442703 - y: 4140717.57991 - z: 0.0 - theta: 1.30624724762 - kappa: -0.00153415610474 - s: 6.50002879234 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.468858 - y: 4140717.67643 - z: 0.0 - theta: 1.30609483416 - kappa: -0.00151246160219 - s: 6.6000288942 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.495027 - y: 4140717.77295 - z: 0.0 - theta: 1.30594507752 - kappa: -0.00148090294466 - s: 6.70002897533 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.521211 - y: 4140717.86946 - z: 0.0 - theta: 1.30579900226 - kappa: -0.00143910504458 - s: 6.80002903846 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.547408 - y: 4140717.96597 - z: 0.0 - theta: 1.30565761187 - kappa: -0.00138668091018 - s: 6.90002908663 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.573619 - y: 4140718.06247 - z: 0.0 - theta: 1.30552202285 - kappa: -0.00132325867065 - s: 7.00002912212 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.599843 - y: 4140718.15897 - z: 0.0 - theta: 1.30539334715 - kappa: -0.00124845805191 - s: 7.10002914754 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.626079 - y: 4140718.25547 - z: 0.0 - theta: 1.30527272093 - kappa: -0.00116189554695 - s: 7.20002916448 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.652325 - y: 4140718.35196 - z: 0.0 - theta: 1.30516136976 - kappa: -0.00106319885268 - s: 7.3000291752 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.678583 - y: 4140718.44845 - z: 0.0 - theta: 1.30506050254 - kappa: -0.000951983834846 - s: 7.40002918204 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.704849 - y: 4140718.54494 - z: 0.0 - theta: 1.30497139724 - kappa: -0.000827873030578 - s: 7.50002918566 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.731123 - y: 4140718.64143 - z: 0.0 - theta: 1.30489537743 - kappa: -0.000690491088724 - s: 7.60002918779 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.757404 - y: 4140718.73791 - z: 0.0 - theta: 1.30483375521 - kappa: -0.000539450916034 - s: 7.70002918826 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.78369 - y: 4140718.8344 - z: 0.0 - theta: 1.30478794651 - kappa: -0.000374381012138 - s: 7.80002918866 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.80998 - y: 4140718.93088 - z: 0.0 - theta: 1.30475936563 - kappa: -0.000194900655533 - s: 7.90002918807 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.836272 - y: 4140719.02736 - z: 0.0 - theta: 1.30474945736 - kappa: -6.26856262368e-07 - s: 8.00002918859 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.836272 - y: 4140719.02736 - z: 0.0 - theta: 1.30474945736 - kappa: -6.26856262344e-07 - s: 8.00002918859 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.862564 - y: 4140719.12384 - z: 0.0 - theta: 1.30474938302 - kappa: -9.68685020214e-07 - s: 8.10002918823 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.888856 - y: 4140719.22032 - z: 0.0 - theta: 1.30474926719 - kappa: -1.29950228336e-06 - s: 8.20002918841 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.915148 - y: 4140719.31681 - z: 0.0 - theta: 1.30474911862 - kappa: -1.62127430049e-06 - s: 8.30002918861 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.94144 - y: 4140719.41329 - z: 0.0 - theta: 1.30474894952 - kappa: -1.93735894272e-06 - s: 8.40002918848 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.967732 - y: 4140719.50977 - z: 0.0 - theta: 1.30474873221 - kappa: -2.23954544818e-06 - s: 8.50002918832 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.994024 - y: 4140719.60625 - z: 0.0 - theta: 1.30474849482 - kappa: -2.53568132206e-06 - s: 8.60002918828 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.020316 - y: 4140719.70273 - z: 0.0 - theta: 1.3047482302 - kappa: -2.82361504257e-06 - s: 8.70002918849 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.046608 - y: 4140719.79921 - z: 0.0 - theta: 1.30474792861 - kappa: -3.09987699578e-06 - s: 8.80002918842 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.0729 - y: 4140719.8957 - z: 0.0 - theta: 1.30474760965 - kappa: -3.37050920188e-06 - s: 8.90002918843 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.099192 - y: 4140719.99218 - z: 0.0 - theta: 1.30474725726 - kappa: -3.63006253506e-06 - s: 9.00002918822 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.125484 - y: 4140720.08866 - z: 0.0 - theta: 1.30474687999 - kappa: -3.88092877646e-06 - s: 9.10002918829 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.151776 - y: 4140720.18514 - z: 0.0 - theta: 1.30474648668 - kappa: -4.12618977537e-06 - s: 9.20002918858 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.178069 - y: 4140720.28162 - z: 0.0 - theta: 1.3047460556 - kappa: -4.35752961308e-06 - s: 9.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.204361 - y: 4140720.37811 - z: 0.0 - theta: 1.30474560983 - kappa: -4.58313259271e-06 - s: 9.40002918843 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.230653 - y: 4140720.47459 - z: 0.0 - theta: 1.30474514278 - kappa: -4.80042825954e-06 - s: 9.50002918851 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.256946 - y: 4140720.57107 - z: 0.0 - theta: 1.30474464859 - kappa: -5.00644804422e-06 - s: 9.60002918827 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.283238 - y: 4140720.66755 - z: 0.0 - theta: 1.30474414148 - kappa: -5.20692019429e-06 - s: 9.70002918851 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.309531 - y: 4140720.76403 - z: 0.0 - theta: 1.30474360925 - kappa: -5.39625266319e-06 - s: 9.80002918842 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.335823 - y: 4140720.86051 - z: 0.0 - theta: 1.30474305951 - kappa: -5.57724953662e-06 - s: 9.90002918861 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.362116 - y: 4140720.95699 - z: 0.0 - theta: 1.30474249804 - kappa: -5.75266297104e-06 - s: 10.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.388408 - y: 4140721.05348 - z: 0.0 - theta: 1.30474190968 - kappa: -5.91425937371e-06 - s: 10.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.414701 - y: 4140721.14996 - z: 0.0 - theta: 1.30474131148 - kappa: -6.07036573232e-06 - s: 10.2000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.440994 - y: 4140721.24644 - z: 0.0 - theta: 1.30474069821 - kappa: -6.21806620843e-06 - s: 10.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.467287 - y: 4140721.34292 - z: 0.0 - theta: 1.30474006713 - kappa: -6.35487998651e-06 - s: 10.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.49358 - y: 4140721.4394 - z: 0.0 - theta: 1.30473942751 - kappa: -6.48622820529e-06 - s: 10.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.519872 - y: 4140721.53588 - z: 0.0 - theta: 1.3047387713 - kappa: -6.60638251443e-06 - s: 10.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.546165 - y: 4140721.63237 - z: 0.0 - theta: 1.30473810452 - kappa: -6.71854602418e-06 - s: 10.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.572459 - y: 4140721.72885 - z: 0.0 - theta: 1.30473743015 - kappa: -6.82498978804e-06 - s: 10.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.598752 - y: 4140721.82533 - z: 0.0 - theta: 1.30473674014 - kappa: -6.91804336098e-06 - s: 10.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.625045 - y: 4140721.92181 - z: 0.0 - theta: 1.30473604462 - kappa: -7.0056889368e-06 - s: 11.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.651338 - y: 4140722.01829 - z: 0.0 - theta: 1.3047353405 - kappa: -7.08483666616e-06 - s: 11.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.677631 - y: 4140722.11477 - z: 0.0 - theta: 1.30473462742 - kappa: -7.15348014568e-06 - s: 11.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.703925 - y: 4140722.21125 - z: 0.0 - theta: 1.3047339101 - kappa: -7.21674010027e-06 - s: 11.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.730218 - y: 4140722.30774 - z: 0.0 - theta: 1.30473318496 - kappa: -7.26875851411e-06 - s: 11.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.756512 - y: 4140722.40422 - z: 0.0 - theta: 1.30473245571 - kappa: -7.31312419496e-06 - s: 11.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.782806 - y: 4140722.5007 - z: 0.0 - theta: 1.30473172331 - kappa: -7.35164046144e-06 - s: 11.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.809099 - y: 4140722.59718 - z: 0.0 - theta: 1.304730986 - kappa: -7.377186608e-06 - s: 11.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.835393 - y: 4140722.69366 - z: 0.0 - theta: 1.30473024745 - kappa: -7.39740676421e-06 - s: 11.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.861687 - y: 4140722.79014 - z: 0.0 - theta: 1.30472950702 - kappa: -7.40904374078e-06 - s: 11.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.887981 - y: 4140722.88662 - z: 0.0 - theta: 1.30472876598 - kappa: -7.41055215666e-06 - s: 12.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.914275 - y: 4140722.9831 - z: 0.0 - theta: 1.30472802496 - kappa: -7.40675904275e-06 - s: 12.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.940569 - y: 4140723.07959 - z: 0.0 - theta: 1.30472728509 - kappa: -7.39168338096e-06 - s: 12.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.966863 - y: 4140723.17607 - z: 0.0 - theta: 1.30472654713 - kappa: -7.36928630582e-06 - s: 12.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.993157 - y: 4140723.27255 - z: 0.0 - theta: 1.30472581073 - kappa: -7.34091681207e-06 - s: 12.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.019451 - y: 4140723.36903 - z: 0.0 - theta: 1.30472507966 - kappa: -7.29999048748e-06 - s: 12.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.045746 - y: 4140723.46551 - z: 0.0 - theta: 1.30472435154 - kappa: -7.25382014485e-06 - s: 12.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.07204 - y: 4140723.56199 - z: 0.0 - theta: 1.30472362848 - kappa: -7.19898794884e-06 - s: 12.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.098335 - y: 4140723.65847 - z: 0.0 - theta: 1.30472291273 - kappa: -7.13439611474e-06 - s: 12.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.124629 - y: 4140723.75495 - z: 0.0 - theta: 1.30472220118 - kappa: -7.06458471461e-06 - s: 12.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.150924 - y: 4140723.85143 - z: 0.0 - theta: 1.30472149993 - kappa: -6.98345641808e-06 - s: 13.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.177218 - y: 4140723.94792 - z: 0.0 - theta: 1.30472080619 - kappa: -6.89533127481e-06 - s: 13.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.203513 - y: 4140724.0444 - z: 0.0 - theta: 1.304720119 - kappa: -6.80111739957e-06 - s: 13.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.229808 - y: 4140724.14088 - z: 0.0 - theta: 1.30471944685 - kappa: -6.694753208e-06 - s: 13.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.256103 - y: 4140724.23736 - z: 0.0 - theta: 1.3047187818 - kappa: -6.58322694788e-06 - s: 13.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.282398 - y: 4140724.33384 - z: 0.0 - theta: 1.30471812899 - kappa: -6.46296685234e-06 - s: 13.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.308693 - y: 4140724.43032 - z: 0.0 - theta: 1.30471749092 - kappa: -6.33330928263e-06 - s: 13.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.334988 - y: 4140724.5268 - z: 0.0 - theta: 1.30471686117 - kappa: -6.19851409252e-06 - s: 13.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.361283 - y: 4140724.62328 - z: 0.0 - theta: 1.30471625108 - kappa: -6.05237435612e-06 - s: 13.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.387578 - y: 4140724.71976 - z: 0.0 - theta: 1.30471565367 - kappa: -5.89955559365e-06 - s: 13.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.413873 - y: 4140724.81624 - z: 0.0 - theta: 1.30471506805 - kappa: -5.74053850406e-06 - s: 14.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.440169 - y: 4140724.91273 - z: 0.0 - theta: 1.3047145067 - kappa: -5.56977086223e-06 - s: 14.1000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.466464 - y: 4140725.00921 - z: 0.0 - theta: 1.30471395652 - kappa: -5.39392309538e-06 - s: 14.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.492759 - y: 4140725.10569 - z: 0.0 - theta: 1.30471342599 - kappa: -5.20927623855e-06 - s: 14.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.519055 - y: 4140725.20217 - z: 0.0 - theta: 1.30471291718 - kappa: -5.01558733585e-06 - s: 14.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.54535 - y: 4140725.29865 - z: 0.0 - theta: 1.30471242073 - kappa: -4.81684275867e-06 - s: 14.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.571646 - y: 4140725.39513 - z: 0.0 - theta: 1.3047119535 - kappa: -4.60673272972e-06 - s: 14.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.597941 - y: 4140725.49161 - z: 0.0 - theta: 1.30471150371 - kappa: -4.39025476959e-06 - s: 14.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.624237 - y: 4140725.58809 - z: 0.0 - theta: 1.30471107117 - kappa: -4.16747563336e-06 - s: 14.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.650533 - y: 4140725.68457 - z: 0.0 - theta: 1.30471067167 - kappa: -3.93333900051e-06 - s: 14.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.676828 - y: 4140725.78105 - z: 0.0 - theta: 1.30471028735 - kappa: -3.69420420218e-06 - s: 15.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.703124 - y: 4140725.87753 - z: 0.0 - theta: 1.30470993029 - kappa: -3.44621182432e-06 - s: 15.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.72942 - y: 4140725.97401 - z: 0.0 - theta: 1.30470960149 - kappa: -3.18952613171e-06 - s: 15.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.755716 - y: 4140726.07049 - z: 0.0 - theta: 1.30470928904 - kappa: -2.92786673426e-06 - s: 15.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.782012 - y: 4140726.16698 - z: 0.0 - theta: 1.30470901552 - kappa: -2.65482777411e-06 - s: 15.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.808307 - y: 4140726.26346 - z: 0.0 - theta: 1.30470876379 - kappa: -2.37572528444e-06 - s: 15.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.834603 - y: 4140726.35994 - z: 0.0 - theta: 1.30470853504 - kappa: -2.09022554269e-06 - s: 15.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.860899 - y: 4140726.45642 - z: 0.0 - theta: 1.30470834761 - kappa: -1.79375471094e-06 - s: 15.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.887195 - y: 4140726.5529 - z: 0.0 - theta: 1.30470817929 - kappa: -1.49236771644e-06 - s: 15.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.913491 - y: 4140726.64938 - z: 0.0 - theta: 1.30470804607 - kappa: -1.18207145863e-06 - s: 15.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.939787 - y: 4140726.74586 - z: 0.0 - theta: 1.30470794719 - kappa: -8.63423973345e-07 - s: 16.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.939787 - y: 4140726.74586 - z: 0.0 - theta: 1.30470794719 - kappa: -8.63423973345e-07 - s: 16.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.966083 - y: 4140726.84234 - z: 0.0 - theta: 1.3047078686 - kappa: -5.39884804711e-07 - s: 16.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.992379 - y: 4140726.93882 - z: 0.0 - theta: 1.30470783882 - kappa: -2.04958810069e-07 - s: 16.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.018675 - y: 4140727.0353 - z: 0.0 - theta: 1.30470783478 - kappa: 1.3573296074e-07 - s: 16.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.044971 - y: 4140727.13178 - z: 0.0 - theta: 1.30470785968 - kappa: 4.8291126109e-07 - s: 16.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.071267 - y: 4140727.22826 - z: 0.0 - theta: 1.30470793344 - kappa: 8.33226725645e-07 - s: 16.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.097563 - y: 4140727.32474 - z: 0.0 - theta: 1.30470802906 - kappa: 1.17767194403e-06 - s: 16.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.123859 - y: 4140727.42122 - z: 0.0 - theta: 1.30470816473 - kappa: 1.50443069e-06 - s: 16.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.150155 - y: 4140727.51771 - z: 0.0 - theta: 1.30470833367 - kappa: 1.81430037037e-06 - s: 16.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.176451 - y: 4140727.61419 - z: 0.0 - theta: 1.30470852235 - kappa: 2.11406852533e-06 - s: 16.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.202746 - y: 4140727.71067 - z: 0.0 - theta: 1.30470875464 - kappa: 2.39036954383e-06 - s: 17.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.229042 - y: 4140727.80715 - z: 0.0 - theta: 1.30470900617 - kappa: 2.65564270981e-06 - s: 17.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.255338 - y: 4140727.90363 - z: 0.0 - theta: 1.3047092808 - kappa: 2.90768356668e-06 - s: 17.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.281634 - y: 4140728.00011 - z: 0.0 - theta: 1.30470958821 - kappa: 3.13962006141e-06 - s: 17.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.30793 - y: 4140728.09659 - z: 0.0 - theta: 1.30470990998 - kappa: 3.36234674899e-06 - s: 17.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.334225 - y: 4140728.19307 - z: 0.0 - theta: 1.30471025789 - kappa: 3.56780472847e-06 - s: 17.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.360521 - y: 4140728.28955 - z: 0.0 - theta: 1.30471062588 - kappa: 3.75886560397e-06 - s: 17.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.386817 - y: 4140728.38603 - z: 0.0 - theta: 1.30471100608 - kappa: 3.94109589379e-06 - s: 17.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.413112 - y: 4140728.48251 - z: 0.0 - theta: 1.30471141275 - kappa: 4.10255430134e-06 - s: 17.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.439408 - y: 4140728.57899 - z: 0.0 - theta: 1.30471183002 - kappa: 4.25478966657e-06 - s: 17.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.465704 - y: 4140728.67547 - z: 0.0 - theta: 1.30471226087 - kappa: 4.39521704152e-06 - s: 18.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.491999 - y: 4140728.77195 - z: 0.0 - theta: 1.30471270916 - kappa: 4.51861585425e-06 - s: 18.1000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.518295 - y: 4140728.86844 - z: 0.0 - theta: 1.30471316498 - kappa: 4.63407584368e-06 - s: 18.2000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.54459 - y: 4140728.96492 - z: 0.0 - theta: 1.30471363436 - kappa: 4.73437867582e-06 - s: 18.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.570885 - y: 4140729.0614 - z: 0.0 - theta: 1.30471411289 - kappa: 4.82267303107e-06 - s: 18.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.597181 - y: 4140729.15788 - z: 0.0 - theta: 1.3047145971 - kappa: 4.90340779569e-06 - s: 18.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.623476 - y: 4140729.25436 - z: 0.0 - theta: 1.30471509256 - kappa: 4.9661694651e-06 - s: 18.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.649771 - y: 4140729.35084 - z: 0.0 - theta: 1.30471559165 - kappa: 5.02140952179e-06 - s: 18.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.676066 - y: 4140729.44732 - z: 0.0 - theta: 1.30471609573 - kappa: 5.066369381e-06 - s: 18.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.702362 - y: 4140729.5438 - z: 0.0 - theta: 1.30471660458 - kappa: 5.09727311843e-06 - s: 18.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.728657 - y: 4140729.64028 - z: 0.0 - theta: 1.30471711516 - kappa: 5.12150903934e-06 - s: 19.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.754952 - y: 4140729.73676 - z: 0.0 - theta: 1.30471762819 - kappa: 5.13280282183e-06 - s: 19.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.781247 - y: 4140729.83324 - z: 0.0 - theta: 1.30471814154 - kappa: 5.13437335165e-06 - s: 19.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.807542 - y: 4140729.92973 - z: 0.0 - theta: 1.30471865508 - kappa: 5.12965529718e-06 - s: 19.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.833837 - y: 4140730.02621 - z: 0.0 - theta: 1.30471916668 - kappa: 5.10986639146e-06 - s: 19.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.860131 - y: 4140730.12269 - z: 0.0 - theta: 1.30471967651 - kappa: 5.08415386964e-06 - s: 19.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.886426 - y: 4140730.21917 - z: 0.0 - theta: 1.30472018376 - kappa: 5.04979238773e-06 - s: 19.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.912721 - y: 4140730.31565 - z: 0.0 - theta: 1.30472068568 - kappa: 5.0042437792e-06 - s: 19.7000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.939016 - y: 4140730.41213 - z: 0.0 - theta: 1.30472118453 - kappa: 4.9532983518e-06 - s: 19.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.96531 - y: 4140730.50861 - z: 0.0 - theta: 1.30472167633 - kappa: 4.89172924612e-06 - s: 19.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.991605 - y: 4140730.60509 - z: 0.0 - theta: 1.30472216163 - kappa: 4.82261864108e-06 - s: 20.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.017899 - y: 4140730.70157 - z: 0.0 - theta: 1.30472264253 - kappa: 4.7484144838e-06 - s: 20.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.044194 - y: 4140730.79805 - z: 0.0 - theta: 1.30472311065 - kappa: 4.66229706983e-06 - s: 20.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.070488 - y: 4140730.89454 - z: 0.0 - theta: 1.30472357294 - kappa: 4.57167459009e-06 - s: 20.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.096783 - y: 4140730.99102 - z: 0.0 - theta: 1.30472402625 - kappa: 4.47413783847e-06 - s: 20.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.123077 - y: 4140731.0875 - z: 0.0 - theta: 1.30472446656 - kappa: 4.36817943903e-06 - s: 20.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.149372 - y: 4140731.18398 - z: 0.0 - theta: 1.30472490002 - kappa: 4.25809519137e-06 - s: 20.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.175666 - y: 4140731.28046 - z: 0.0 - theta: 1.30472531865 - kappa: 4.13980917542e-06 - s: 20.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.20196 - y: 4140731.37694 - z: 0.0 - theta: 1.30472572583 - kappa: 4.01605988317e-06 - s: 20.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.228254 - y: 4140731.47342 - z: 0.0 - theta: 1.30472612474 - kappa: 3.88836797744e-06 - s: 20.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.254548 - y: 4140731.5699 - z: 0.0 - theta: 1.30472650294 - kappa: 3.75211198632e-06 - s: 21.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.280843 - y: 4140731.66638 - z: 0.0 - theta: 1.30472687222 - kappa: 3.61262187814e-06 - s: 21.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.307137 - y: 4140731.76287 - z: 0.0 - theta: 1.30472722741 - kappa: 3.46805566543e-06 - s: 21.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.333431 - y: 4140731.85935 - z: 0.0 - theta: 1.30472756426 - kappa: 3.31772971211e-06 - s: 21.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.359725 - y: 4140731.95583 - z: 0.0 - theta: 1.30472789148 - kappa: 3.16454884866e-06 - s: 21.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.386019 - y: 4140732.05231 - z: 0.0 - theta: 1.30472819796 - kappa: 3.00569160897e-06 - s: 21.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.412313 - y: 4140732.14879 - z: 0.0 - theta: 1.30472848977 - kappa: 2.84334574066e-06 - s: 21.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.438607 - y: 4140732.24527 - z: 0.0 - theta: 1.30472877027 - kappa: 2.67831171246e-06 - s: 21.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.464901 - y: 4140732.34175 - z: 0.0 - theta: 1.3047290249 - kappa: 2.50795916315e-06 - s: 21.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.491195 - y: 4140732.43823 - z: 0.0 - theta: 1.30472926855 - kappa: 2.3356434145e-06 - s: 21.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.517488 - y: 4140732.53472 - z: 0.0 - theta: 1.3047294944 - kappa: 2.16019324719e-06 - s: 22.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.543782 - y: 4140732.6312 - z: 0.0 - theta: 1.30472969874 - kappa: 1.9815416397e-06 - s: 22.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.570076 - y: 4140732.72768 - z: 0.0 - theta: 1.30472989169 - kappa: 1.80130603143e-06 - s: 22.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.59637 - y: 4140732.82416 - z: 0.0 - theta: 1.30473005996 - kappa: 1.61802296452e-06 - s: 22.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.622664 - y: 4140732.92064 - z: 0.0 - theta: 1.30473021197 - kappa: 1.43312231205e-06 - s: 22.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.648958 - y: 4140733.01712 - z: 0.0 - theta: 1.30473035061 - kappa: 1.24689150666e-06 - s: 22.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.675251 - y: 4140733.1136 - z: 0.0 - theta: 1.30473046083 - kappa: 1.05848411739e-06 - s: 22.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.701545 - y: 4140733.21008 - z: 0.0 - theta: 1.30473055902 - kappa: 8.69384424187e-07 - s: 22.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.727839 - y: 4140733.30657 - z: 0.0 - theta: 1.30473063724 - kappa: 6.7919555778e-07 - s: 22.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.754133 - y: 4140733.40305 - z: 0.0 - theta: 1.30473069286 - kappa: 4.8825993155e-07 - s: 22.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.780426 - y: 4140733.49953 - z: 0.0 - theta: 1.30473073633 - kappa: 2.97011195434e-07 - s: 23.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.80672 - y: 4140733.59601 - z: 0.0 - theta: 1.30473075328 - kappa: 1.05447485406e-07 - s: 23.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.833014 - y: 4140733.69249 - z: 0.0 - theta: 1.30473075388 - kappa: -8.59663816551e-08 - s: 23.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.859308 - y: 4140733.78897 - z: 0.0 - theta: 1.30473074013 - kappa: -2.77248808254e-07 - s: 23.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.885601 - y: 4140733.88545 - z: 0.0 - theta: 1.30473069794 - kappa: -4.67669504952e-07 - s: 23.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.911895 - y: 4140733.98194 - z: 0.0 - theta: 1.30473064367 - kappa: -6.57511619381e-07 - s: 23.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.938189 - y: 4140734.07842 - z: 0.0 - theta: 1.30473056892 - kappa: -8.4629406831e-07 - s: 23.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.964483 - y: 4140734.1749 - z: 0.0 - theta: 1.30473047241 - kappa: -1.03347221088e-06 - s: 23.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.990777 - y: 4140734.27138 - z: 0.0 - theta: 1.304730364 - kappa: -1.21969257716e-06 - s: 23.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.01707 - y: 4140734.36786 - z: 0.0 - theta: 1.30473022947 - kappa: -1.4033918312e-06 - s: 23.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.043364 - y: 4140734.46434 - z: 0.0 - theta: 1.30473007986 - kappa: -1.58527742034e-06 - s: 24.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.043364 - y: 4140734.46434 - z: 0.0 - theta: 1.30473007986 - kappa: -1.58527742034e-06 - s: 24.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.069658 - y: 4140734.56082 - z: 0.0 - theta: 1.30472991614 - kappa: -1.76546636833e-06 - s: 24.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.095952 - y: 4140734.6573 - z: 0.0 - theta: 1.30472972634 - kappa: -1.94185887303e-06 - s: 24.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.122246 - y: 4140734.75379 - z: 0.0 - theta: 1.30472952542 - kappa: -2.11640190394e-06 - s: 24.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.14854 - y: 4140734.85027 - z: 0.0 - theta: 1.3047293053 - kappa: -2.28763281754e-06 - s: 24.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.174833 - y: 4140734.94675 - z: 0.0 - theta: 1.30472906607 - kappa: -2.4550119488e-06 - s: 24.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.201127 - y: 4140735.04323 - z: 0.0 - theta: 1.30472881622 - kappa: -2.62016240722e-06 - s: 24.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.227421 - y: 4140735.13971 - z: 0.0 - theta: 1.30472854297 - kappa: -2.77985204564e-06 - s: 24.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.253715 - y: 4140735.23619 - z: 0.0 - theta: 1.30472825718 - kappa: -2.93616778034e-06 - s: 24.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.280009 - y: 4140735.33267 - z: 0.0 - theta: 1.30472795886 - kappa: -3.0891180612e-06 - s: 24.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.306303 - y: 4140735.42915 - z: 0.0 - theta: 1.30472763907 - kappa: -3.23544074838e-06 - s: 25.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.332597 - y: 4140735.52564 - z: 0.0 - theta: 1.30472731013 - kappa: -3.37864305082e-06 - s: 25.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.358891 - y: 4140735.62212 - z: 0.0 - theta: 1.30472696518 - kappa: -3.51617716735e-06 - s: 25.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.385186 - y: 4140735.7186 - z: 0.0 - theta: 1.30472660546 - kappa: -3.64771557984e-06 - s: 25.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.41148 - y: 4140735.81508 - z: 0.0 - theta: 1.3047262374 - kappa: -3.77575439975e-06 - s: 25.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.437774 - y: 4140735.91156 - z: 0.0 - theta: 1.30472585116 - kappa: -3.89528906981e-06 - s: 25.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.464068 - y: 4140736.00804 - z: 0.0 - theta: 1.30472545602 - kappa: -4.00999314498e-06 - s: 25.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.490362 - y: 4140736.10452 - z: 0.0 - theta: 1.30472505141 - kappa: -4.11955935464e-06 - s: 25.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.516657 - y: 4140736.201 - z: 0.0 - theta: 1.30472463206 - kappa: -4.21977033832e-06 - s: 25.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.542951 - y: 4140736.29748 - z: 0.0 - theta: 1.30472420656 - kappa: -4.31558999676e-06 - s: 25.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.569246 - y: 4140736.39397 - z: 0.0 - theta: 1.30472377026 - kappa: -4.40328180028e-06 - s: 26.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.59554 - y: 4140736.49045 - z: 0.0 - theta: 1.3047233251 - kappa: -4.48293748976e-06 - s: 26.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.621834 - y: 4140736.58693 - z: 0.0 - theta: 1.30472287489 - kappa: -4.55782263545e-06 - s: 26.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.648129 - y: 4140736.68341 - z: 0.0 - theta: 1.30472241432 - kappa: -4.62105670082e-06 - s: 26.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.674424 - y: 4140736.77989 - z: 0.0 - theta: 1.30472194949 - kappa: -4.67810698674e-06 - s: 26.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.700718 - y: 4140736.87637 - z: 0.0 - theta: 1.30472147983 - kappa: -4.7281434278e-06 - s: 26.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.727013 - y: 4140736.97285 - z: 0.0 - theta: 1.30472100418 - kappa: -4.76620048378e-06 - s: 26.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.753308 - y: 4140737.06933 - z: 0.0 - theta: 1.30472052639 - kappa: -4.798595241e-06 - s: 26.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.779602 - y: 4140737.16581 - z: 0.0 - theta: 1.30472004516 - kappa: -4.82029891136e-06 - s: 26.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.805897 - y: 4140737.26229 - z: 0.0 - theta: 1.30471956243 - kappa: -4.83202952757e-06 - s: 26.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.832192 - y: 4140737.35878 - z: 0.0 - theta: 1.30471907894 - kappa: -4.83771861638e-06 - s: 27.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.858487 - y: 4140737.45526 - z: 0.0 - theta: 1.30471859564 - kappa: -4.82850614085e-06 - s: 27.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.884782 - y: 4140737.55174 - z: 0.0 - theta: 1.3047181136 - kappa: -4.81186016789e-06 - s: 27.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.911077 - y: 4140737.64822 - z: 0.0 - theta: 1.30471763309 - kappa: -4.78622084995e-06 - s: 27.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.937372 - y: 4140737.7447 - z: 0.0 - theta: 1.30471715722 - kappa: -4.74608142811e-06 - s: 27.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.963667 - y: 4140737.84118 - z: 0.0 - theta: 1.30471668421 - kappa: -4.69900870682e-06 - s: 27.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.989962 - y: 4140737.93766 - z: 0.0 - theta: 1.30471621742 - kappa: -4.63857816037e-06 - s: 27.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.016257 - y: 4140738.03414 - z: 0.0 - theta: 1.30471575781 - kappa: -4.56634105976e-06 - s: 27.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.042553 - y: 4140738.13062 - z: 0.0 - theta: 1.30471530273 - kappa: -4.48679142487e-06 - s: 27.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.068848 - y: 4140738.2271 - z: 0.0 - theta: 1.30471486125 - kappa: -4.38898625659e-06 - s: 27.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.095143 - y: 4140738.32359 - z: 0.0 - theta: 1.30471442729 - kappa: -4.28260131164e-06 - s: 28.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.121438 - y: 4140738.42007 - z: 0.0 - theta: 1.30471400305 - kappa: -4.16514006145e-06 - s: 28.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.147734 - y: 4140738.51655 - z: 0.0 - theta: 1.30471359585 - kappa: -4.03076141908e-06 - s: 28.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.174029 - y: 4140738.61303 - z: 0.0 - theta: 1.30471319753 - kappa: -3.88817846729e-06 - s: 28.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.200325 - y: 4140738.70951 - z: 0.0 - theta: 1.3047128175 - kappa: -3.72946751763e-06 - s: 28.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.22662 - y: 4140738.80599 - z: 0.0 - theta: 1.3047124545 - kappa: -3.55721994853e-06 - s: 28.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.252916 - y: 4140738.90247 - z: 0.0 - theta: 1.30471210236 - kappa: -3.37638883791e-06 - s: 28.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.279211 - y: 4140738.99895 - z: 0.0 - theta: 1.30471178018 - kappa: -3.17384482828e-06 - s: 28.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.305507 - y: 4140739.09543 - z: 0.0 - theta: 1.30471147242 - kappa: -2.96167819601e-06 - s: 28.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.331803 - y: 4140739.19191 - z: 0.0 - theta: 1.30471118453 - kappa: -2.73624890534e-06 - s: 28.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.358098 - y: 4140739.28839 - z: 0.0 - theta: 1.30471092771 - kappa: -2.49158839361e-06 - s: 29.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.384394 - y: 4140739.38487 - z: 0.0 - theta: 1.3047106868 - kappa: -2.23745258641e-06 - s: 29.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.41069 - y: 4140739.48135 - z: 0.0 - theta: 1.30471047878 - kappa: -1.96431525933e-06 - s: 29.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.436985 - y: 4140739.57784 - z: 0.0 - theta: 1.30471029871 - kappa: -1.67601471227e-06 - s: 29.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.463281 - y: 4140739.67432 - z: 0.0 - theta: 1.30471013684 - kappa: -1.37785965312e-06 - s: 29.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.489577 - y: 4140739.7708 - z: 0.0 - theta: 1.30471002439 - kappa: -1.05443103844e-06 - s: 29.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.515872 - y: 4140739.86728 - z: 0.0 - theta: 1.30470993375 - kappa: -7.20440419285e-07 - s: 29.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.542168 - y: 4140739.96376 - z: 0.0 - theta: 1.30470987524 - kappa: -3.70897464002e-07 - s: 29.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.568464 - y: 4140740.06024 - z: 0.0 - theta: 1.30470986319 - kappa: -5.34310441226e-09 - s: 29.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.59476 - y: 4140740.15672 - z: 0.0 - theta: 1.30470987415 - kappa: 3.60215874987e-07 - s: 29.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.621056 - y: 4140740.2532 - z: 0.0 - theta: 1.30470993162 - kappa: 7.09710835896e-07 - s: 30.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.647351 - y: 4140740.34968 - z: 0.0 - theta: 1.30471002117 - kappa: 1.04364704453e-06 - s: 30.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.673647 - y: 4140740.44616 - z: 0.0 - theta: 1.30471013256 - kappa: 1.36698584742e-06 - s: 30.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.699943 - y: 4140740.54264 - z: 0.0 - theta: 1.30471029333 - kappa: 1.66503402305e-06 - s: 30.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.726238 - y: 4140740.63912 - z: 0.0 - theta: 1.30471047228 - kappa: 1.95321570119e-06 - s: 30.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.752534 - y: 4140740.7356 - z: 0.0 - theta: 1.30471067921 - kappa: 2.22619892732e-06 - s: 30.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.77883 - y: 4140740.83209 - z: 0.0 - theta: 1.30471091897 - kappa: 2.48018007536e-06 - s: 30.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.805126 - y: 4140740.92857 - z: 0.0 - theta: 1.30471117463 - kappa: 2.72467772754e-06 - s: 30.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.831421 - y: 4140741.02505 - z: 0.0 - theta: 1.30471146136 - kappa: 2.94991441682e-06 - s: 30.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.857717 - y: 4140741.12153 - z: 0.0 - theta: 1.30471176793 - kappa: 3.16189908007e-06 - s: 30.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.884012 - y: 4140741.21801 - z: 0.0 - theta: 1.30471208893 - kappa: 3.36424090998e-06 - s: 31.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.910308 - y: 4140741.31449 - z: 0.0 - theta: 1.30471243983 - kappa: 3.54488250699e-06 - s: 31.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.936603 - y: 4140741.41097 - z: 0.0 - theta: 1.30471280158 - kappa: 3.71694126452e-06 - s: 31.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.962899 - y: 4140741.50745 - z: 0.0 - theta: 1.30471318036 - kappa: 3.87545021994e-06 - s: 31.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.989194 - y: 4140741.60393 - z: 0.0 - theta: 1.30471357739 - kappa: 4.01785349601e-06 - s: 31.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.01549 - y: 4140741.70041 - z: 0.0 - theta: 1.30471398329 - kappa: 4.15205695121e-06 - s: 31.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.041785 - y: 4140741.79689 - z: 0.0 - theta: 1.30471440622 - kappa: 4.2693421842e-06 - s: 31.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.06808 - y: 4140741.89337 - z: 0.0 - theta: 1.30471483883 - kappa: 4.37557775901e-06 - s: 31.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.094376 - y: 4140741.98985 - z: 0.0 - theta: 1.30471527898 - kappa: 4.47322956926e-06 - s: 31.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.120671 - y: 4140742.08634 - z: 0.0 - theta: 1.30471573268 - kappa: 4.5526672153e-06 - s: 31.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.146966 - y: 4140742.18282 - z: 0.0 - theta: 1.30471619093 - kappa: 4.62480571814e-06 - s: 32.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.146966 - y: 4140742.18282 - z: 0.0 - theta: 1.30471619093 - kappa: 4.62480571814e-06 - s: 32.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.173261 - y: 4140742.2793 - z: 0.0 - theta: 1.30471665633 - kappa: 4.6851475685e-06 - s: 32.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.199556 - y: 4140742.37578 - z: 0.0 - theta: 1.30471712795 - kappa: 4.73217575426e-06 - s: 32.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.225851 - y: 4140742.47226 - z: 0.0 - theta: 1.30471760243 - kappa: 4.77228781753e-06 - s: 32.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.252146 - y: 4140742.56874 - z: 0.0 - theta: 1.30471808155 - kappa: 4.79792889138e-06 - s: 32.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.278441 - y: 4140742.66522 - z: 0.0 - theta: 1.3047185622 - kappa: 4.81461824928e-06 - s: 32.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.304736 - y: 4140742.7617 - z: 0.0 - theta: 1.30471904411 - kappa: 4.82388737805e-06 - s: 32.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.331031 - y: 4140742.85818 - z: 0.0 - theta: 1.30471952623 - kappa: 4.81832398199e-06 - s: 32.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.357326 - y: 4140742.95466 - z: 0.0 - theta: 1.30472000759 - kappa: 4.80674513799e-06 - s: 32.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.38362 - y: 4140743.05115 - z: 0.0 - theta: 1.30472048747 - kappa: 4.78522725858e-06 - s: 32.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.409915 - y: 4140743.14763 - z: 0.0 - theta: 1.30472096395 - kappa: 4.75308326244e-06 - s: 33.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.43621 - y: 4140743.24411 - z: 0.0 - theta: 1.30472143829 - kappa: 4.71530683282e-06 - s: 33.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.462504 - y: 4140743.34059 - z: 0.0 - theta: 1.30472190669 - kappa: 4.66561111063e-06 - s: 33.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.488799 - y: 4140743.43707 - z: 0.0 - theta: 1.30472237029 - kappa: 4.60895712087e-06 - s: 33.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.515094 - y: 4140743.53355 - z: 0.0 - theta: 1.30472282965 - kappa: 4.54615090976e-06 - s: 33.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.541388 - y: 4140743.63003 - z: 0.0 - theta: 1.30472327874 - kappa: 4.47178929452e-06 - s: 33.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.567683 - y: 4140743.72651 - z: 0.0 - theta: 1.30472372281 - kappa: 4.39269590338e-06 - s: 33.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.593977 - y: 4140743.82299 - z: 0.0 - theta: 1.30472415808 - kappa: 4.30562556788e-06 - s: 33.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.620271 - y: 4140743.91948 - z: 0.0 - theta: 1.30472458263 - kappa: 4.21051212293e-06 - s: 33.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.646566 - y: 4140744.01596 - z: 0.0 - theta: 1.30472500108 - kappa: 4.11104990632e-06 - s: 33.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.67286 - y: 4140744.11244 - z: 0.0 - theta: 1.30472540488 - kappa: 4.00232456832e-06 - s: 34.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.699154 - y: 4140744.20892 - z: 0.0 - theta: 1.30472579931 - kappa: 3.88852985632e-06 - s: 34.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.725448 - y: 4140744.3054 - z: 0.0 - theta: 1.30472618489 - kappa: 3.76995543192e-06 - s: 34.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.751743 - y: 4140744.40188 - z: 0.0 - theta: 1.30472655246 - kappa: 3.64299813555e-06 - s: 34.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.778037 - y: 4140744.49836 - z: 0.0 - theta: 1.30472691175 - kappa: 3.51259270282e-06 - s: 34.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.804331 - y: 4140744.59484 - z: 0.0 - theta: 1.30472725639 - kappa: 3.37627692179e-06 - s: 34.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.830625 - y: 4140744.69132 - z: 0.0 - theta: 1.30472758518 - kappa: 3.23439644035e-06 - s: 34.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.856919 - y: 4140744.78781 - z: 0.0 - theta: 1.30472790491 - kappa: 3.08945081576e-06 - s: 34.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.883213 - y: 4140744.88429 - z: 0.0 - theta: 1.30472820335 - kappa: 2.93800274986e-06 - s: 34.8000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.909507 - y: 4140744.98077 - z: 0.0 - theta: 1.30472848942 - kappa: 2.78326960043e-06 - s: 34.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.935801 - y: 4140745.07725 - z: 0.0 - theta: 1.30472876304 - kappa: 2.62523378862e-06 - s: 35.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.962095 - y: 4140745.17373 - z: 0.0 - theta: 1.30472901354 - kappa: 2.46188300199e-06 - s: 35.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.988389 - y: 4140745.27021 - z: 0.0 - theta: 1.30472925353 - kappa: 2.29636768678e-06 - s: 35.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.014683 - y: 4140745.36669 - z: 0.0 - theta: 1.30472947462 - kappa: 2.12711316549e-06 - s: 35.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.040976 - y: 4140745.46317 - z: 0.0 - theta: 1.30472967674 - kappa: 1.9546677181e-06 - s: 35.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.06727 - y: 4140745.55966 - z: 0.0 - theta: 1.30472986789 - kappa: 1.78044072672e-06 - s: 35.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.093564 - y: 4140745.65614 - z: 0.0 - theta: 1.30473003325 - kappa: 1.60257652642e-06 - s: 35.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.119858 - y: 4140745.75262 - z: 0.0 - theta: 1.30473018471 - kappa: 1.42310689869e-06 - s: 35.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.146152 - y: 4140745.8491 - z: 0.0 - theta: 1.30473032129 - kappa: 1.24191624188e-06 - s: 35.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.172445 - y: 4140745.94558 - z: 0.0 - theta: 1.30473043211 - kappa: 1.05837384977e-06 - s: 35.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.198739 - y: 4140746.04206 - z: 0.0 - theta: 1.30473053122 - kappa: 8.73950513338e-07 - s: 36.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.225033 - y: 4140746.13854 - z: 0.0 - theta: 1.30473060888 - kappa: 6.88063702284e-07 - s: 36.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.251327 - y: 4140746.23502 - z: 0.0 - theta: 1.30473066639 - kappa: 5.01255087019e-07 - s: 36.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.277621 - y: 4140746.33151 - z: 0.0 - theta: 1.30473071202 - kappa: 3.13948507514e-07 - s: 36.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.303914 - y: 4140746.42799 - z: 0.0 - theta: 1.30473072967 - kappa: 1.25974550535e-07 - s: 36.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.330208 - y: 4140746.52447 - z: 0.0 - theta: 1.30473073324 - kappa: -6.20298259751e-08 - s: 36.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.356502 - y: 4140746.62095 - z: 0.0 - theta: 1.30473072074 - kappa: -2.50068979687e-07 - s: 36.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.382796 - y: 4140746.71743 - z: 0.0 - theta: 1.30473068224 - kappa: -4.37601286421e-07 - s: 36.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.409089 - y: 4140746.81391 - z: 0.0 - theta: 1.30473063183 - kappa: -6.24730963309e-07 - s: 36.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.435383 - y: 4140746.91039 - z: 0.0 - theta: 1.30473055925 - kappa: -8.10943756596e-07 - s: 36.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.461677 - y: 4140747.00687 - z: 0.0 - theta: 1.30473046715 - kappa: -9.95913882419e-07 - s: 37.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.487971 - y: 4140747.10336 - z: 0.0 - theta: 1.30473036329 - kappa: -1.18009839858e-06 - s: 37.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.514264 - y: 4140747.19984 - z: 0.0 - theta: 1.30473023165 - kappa: -1.36187582408e-06 - s: 37.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.540558 - y: 4140747.29632 - z: 0.0 - theta: 1.30473008699 - kappa: -1.54221330401e-06 - s: 37.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.566852 - y: 4140747.3928 - z: 0.0 - theta: 1.30472992645 - kappa: -1.72079466645e-06 - s: 37.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.593146 - y: 4140747.48928 - z: 0.0 - theta: 1.30472974191 - kappa: -1.8961152387e-06 - s: 37.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.61944 - y: 4140747.58576 - z: 0.0 - theta: 1.30472954628 - kappa: -2.06974960221e-06 - s: 37.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.645734 - y: 4140747.68224 - z: 0.0 - theta: 1.30472932975 - kappa: -2.23998207333e-06 - s: 37.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.672028 - y: 4140747.77872 - z: 0.0 - theta: 1.30472909599 - kappa: -2.40691203394e-06 - s: 37.8000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.698321 - y: 4140747.87521 - z: 0.0 - theta: 1.3047288516 - kappa: -2.57177280161e-06 - s: 37.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.724615 - y: 4140747.97169 - z: 0.0 - theta: 1.30472858217 - kappa: -2.73104735207e-06 - s: 38.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.750909 - y: 4140748.06817 - z: 0.0 - theta: 1.30472830187 - kappa: -2.88751621354e-06 - s: 38.1000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.777203 - y: 4140748.16465 - z: 0.0 - theta: 1.30472800742 - kappa: -3.04033341261e-06 - s: 38.2000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.803497 - y: 4140748.26113 - z: 0.0 - theta: 1.30472769306 - kappa: -3.18724048064e-06 - s: 38.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.829791 - y: 4140748.35761 - z: 0.0 - theta: 1.30472736949 - kappa: -3.33117774258e-06 - s: 38.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.856086 - y: 4140748.45409 - z: 0.0 - theta: 1.30472702835 - kappa: -3.46912344863e-06 - s: 38.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.88238 - y: 4140748.55057 - z: 0.0 - theta: 1.30472667381 - kappa: -3.60181139523e-06 - s: 38.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.908674 - y: 4140748.64706 - z: 0.0 - theta: 1.30472631079 - kappa: -3.73114654286e-06 - s: 38.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.934968 - y: 4140748.74354 - z: 0.0 - theta: 1.30472592815 - kappa: -3.851611685e-06 - s: 38.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.961262 - y: 4140748.84002 - z: 0.0 - theta: 1.30472553776 - kappa: -3.96800998309e-06 - s: 38.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.987557 - y: 4140748.9365 - z: 0.0 - theta: 1.30472513658 - kappa: -4.07875643559e-06 - s: 39.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.013851 - y: 4140749.03298 - z: 0.0 - theta: 1.30472472159 - kappa: -4.18104797439e-06 - s: 39.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.040145 - y: 4140749.12946 - z: 0.0 - theta: 1.30472430026 - kappa: -4.27908608033e-06 - s: 39.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.06644 - y: 4140749.22594 - z: 0.0 - theta: 1.30472386693 - kappa: -4.36843832614e-06 - s: 39.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.092734 - y: 4140749.32242 - z: 0.0 - theta: 1.30472342544 - kappa: -4.45068211578e-06 - s: 39.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.119028 - y: 4140749.4189 - z: 0.0 - theta: 1.30472297865 - kappa: -4.52828946918e-06 - s: 39.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.145323 - y: 4140749.51539 - z: 0.0 - theta: 1.30472252045 - kappa: -4.59363838835e-06 - s: 39.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.171618 - y: 4140749.61187 - z: 0.0 - theta: 1.30472205845 - kappa: -4.65376385525e-06 - s: 39.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.197912 - y: 4140749.70835 - z: 0.0 - theta: 1.30472159081 - kappa: -4.7061326848e-06 - s: 39.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.224207 - y: 4140749.80483 - z: 0.0 - theta: 1.30472111732 - kappa: -4.74760633179e-06 - s: 39.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.250502 - y: 4140749.90131 - z: 0.0 - theta: 1.30472064137 - kappa: -4.78354288613e-06 - s: 40.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.250502 - y: 4140749.90131 - z: 0.0 - theta: 1.30472064137 - kappa: -4.78354288613e-06 - s: 40.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.276796 - y: 4140749.99779 - z: 0.0 - theta: 1.30472016134 - kappa: -4.807994673e-06 - s: 40.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.303091 - y: 4140750.09427 - z: 0.0 - theta: 1.30471967969 - kappa: -4.82359181654e-06 - s: 40.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.329386 - y: 4140750.19075 - z: 0.0 - theta: 1.30471919693 - kappa: -4.8331066463e-06 - s: 40.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.355681 - y: 4140750.28723 - z: 0.0 - theta: 1.30471871388 - kappa: -4.82719443335e-06 - s: 40.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.381976 - y: 4140750.38371 - z: 0.0 - theta: 1.30471823171 - kappa: -4.81484445872e-06 - s: 40.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.408271 - y: 4140750.4802 - z: 0.0 - theta: 1.30471775094 - kappa: -4.79252849448e-06 - s: 40.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.434566 - y: 4140750.57668 - z: 0.0 - theta: 1.30471727401 - kappa: -4.75698155731e-06 - s: 40.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.460861 - y: 4140750.67316 - z: 0.0 - theta: 1.30471679954 - kappa: -4.71461383956e-06 - s: 40.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.487156 - y: 4140750.76964 - z: 0.0 - theta: 1.30471633137 - kappa: -4.65785790084e-06 - s: 40.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.513451 - y: 4140750.86612 - z: 0.0 - theta: 1.30471586928 - kappa: -4.5906056092e-06 - s: 41.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.539746 - y: 4140750.9626 - z: 0.0 - theta: 1.30471541166 - kappa: -4.51565123935e-06 - s: 41.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.566042 - y: 4140751.05908 - z: 0.0 - theta: 1.30471496719 - kappa: -4.42234441984e-06 - s: 41.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.592337 - y: 4140751.15556 - z: 0.0 - theta: 1.30471452924 - kappa: -4.32131614092e-06 - s: 41.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.618632 - y: 4140751.25204 - z: 0.0 - theta: 1.30471410173 - kappa: -4.2080080218e-06 - s: 41.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.644928 - y: 4140751.34852 - z: 0.0 - theta: 1.30471368938 - kappa: -4.07923760454e-06 - s: 41.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.671223 - y: 4140751.445 - z: 0.0 - theta: 1.30471328543 - kappa: -3.94236270787e-06 - s: 41.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.697518 - y: 4140751.54149 - z: 0.0 - theta: 1.30471290075 - kappa: -3.78809166623e-06 - s: 41.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.723814 - y: 4140751.63797 - z: 0.0 - theta: 1.30471253089 - kappa: -3.62178702857e-06 - s: 41.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.750109 - y: 4140751.73445 - z: 0.0 - theta: 1.30471217266 - kappa: -3.44605609097e-06 - s: 41.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.776405 - y: 4140751.83093 - z: 0.0 - theta: 1.30471184308 - kappa: -3.24915177381e-06 - s: 42.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.802701 - y: 4140751.92741 - z: 0.0 - theta: 1.30471152667 - kappa: -3.04324230862e-06 - s: 42.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.828996 - y: 4140752.02389 - z: 0.0 - theta: 1.3047112319 - kappa: -2.82263472706e-06 - s: 42.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.855292 - y: 4140752.12037 - z: 0.0 - theta: 1.3047109651 - kappa: -2.58443800817e-06 - s: 42.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.881588 - y: 4140752.21685 - z: 0.0 - theta: 1.30471071365 - kappa: -2.3368531317e-06 - s: 42.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.907883 - y: 4140752.31333 - z: 0.0 - theta: 1.30471049716 - kappa: -2.0687598052e-06 - s: 42.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.934179 - y: 4140752.40981 - z: 0.0 - theta: 1.30471030516 - kappa: -1.78720012971e-06 - s: 42.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.960475 - y: 4140752.50629 - z: 0.0 - theta: 1.30471013363 - kappa: -1.4943855339e-06 - s: 42.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.98677 - y: 4140752.60277 - z: 0.0 - theta: 1.3047100082 - kappa: -1.1776811731e-06 - s: 42.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.013066 - y: 4140752.69925 - z: 0.0 - theta: 1.3047099036 - kappa: -8.50688028375e-07 - s: 42.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.039362 - y: 4140752.79574 - z: 0.0 - theta: 1.30470983412 - kappa: -5.06474140661e-07 - s: 43.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.065658 - y: 4140752.89222 - z: 0.0 - theta: 1.30470980674 - kappa: -1.44848532363e-07 - s: 43.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.091954 - y: 4140752.9887 - z: 0.0 - theta: 1.30470980223 - kappa: 2.21129375934e-07 - s: 43.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.118249 - y: 4140753.08518 - z: 0.0 - theta: 1.30470984835 - kappa: 5.74461154704e-07 - s: 43.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.144545 - y: 4140753.18166 - z: 0.0 - theta: 1.30470992332 - kappa: 9.14098133323e-07 - s: 43.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.170841 - y: 4140753.27814 - z: 0.0 - theta: 1.30471002401 - kappa: 1.24152753035e-06 - s: 43.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.197137 - y: 4140753.37462 - z: 0.0 - theta: 1.3047101714 - kappa: 1.54557026101e-06 - s: 43.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.223432 - y: 4140753.4711 - z: 0.0 - theta: 1.30471033752 - kappa: 1.83979041766e-06 - s: 43.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.249728 - y: 4140753.56758 - z: 0.0 - theta: 1.30471053513 - kappa: 2.11731489266e-06 - s: 43.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.276024 - y: 4140753.66406 - z: 0.0 - theta: 1.30471076334 - kappa: 2.37757923778e-06 - s: 43.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.302319 - y: 4140753.76054 - z: 0.0 - theta: 1.30471100799 - kappa: 2.62839287375e-06 - s: 44.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.328615 - y: 4140753.85702 - z: 0.0 - theta: 1.30471128692 - kappa: 2.85854560876e-06 - s: 44.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.354911 - y: 4140753.9535 - z: 0.0 - theta: 1.30471158383 - kappa: 3.07704190803e-06 - s: 44.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.381206 - y: 4140754.04999 - z: 0.0 - theta: 1.30471189783 - kappa: 3.28445873615e-06 - s: 44.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.407502 - y: 4140754.14647 - z: 0.0 - theta: 1.30471224045 - kappa: 3.47177360644e-06 - s: 44.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.433797 - y: 4140754.24295 - z: 0.0 - theta: 1.30471259449 - kappa: 3.65051223748e-06 - s: 44.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.460093 - y: 4140754.33943 - z: 0.0 - theta: 1.30471296794 - kappa: 3.81435720167e-06 - s: 44.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.486388 - y: 4140754.43591 - z: 0.0 - theta: 1.30471335867 - kappa: 3.96355292508e-06 - s: 44.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.512684 - y: 4140754.53239 - z: 0.0 - theta: 1.30471375884 - kappa: 4.10454429201e-06 - s: 44.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.538979 - y: 4140754.62887 - z: 0.0 - theta: 1.30471417818 - kappa: 4.22735068931e-06 - s: 44.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.565274 - y: 4140754.72535 - z: 0.0 - theta: 1.30471460651 - kappa: 4.34043768691e-06 - s: 45.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.59157 - y: 4140754.82183 - z: 0.0 - theta: 1.30471504396 - kappa: 4.44367479421e-06 - s: 45.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.617865 - y: 4140754.91831 - z: 0.0 - theta: 1.30471549483 - kappa: 4.52999336061e-06 - s: 45.2000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.64416 - y: 4140755.01479 - z: 0.0 - theta: 1.3047159508 - kappa: 4.60898206396e-06 - s: 45.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.670455 - y: 4140755.11127 - z: 0.0 - theta: 1.30471641531 - kappa: 4.67498058603e-06 - s: 45.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.69675 - y: 4140755.20776 - z: 0.0 - theta: 1.30471688612 - kappa: 4.72883940963e-06 - s: 45.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.723045 - y: 4140755.30424 - z: 0.0 - theta: 1.30471736032 - kappa: 4.77574025602e-06 - s: 45.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.74934 - y: 4140755.40072 - z: 0.0 - theta: 1.30471784036 - kappa: 4.80703352443e-06 - s: 45.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.775635 - y: 4140755.4972 - z: 0.0 - theta: 1.30471832218 - kappa: 4.83044304234e-06 - s: 45.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.80193 - y: 4140755.59368 - z: 0.0 - theta: 1.30471880592 - kappa: 4.8453336832e-06 - s: 45.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.828225 - y: 4140755.69016 - z: 0.0 - theta: 1.30471929064 - kappa: 4.8463878131e-06 - s: 46.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.85452 - y: 4140755.78664 - z: 0.0 - theta: 1.30471977511 - kappa: 4.84135845799e-06 - s: 46.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.880815 - y: 4140755.88312 - z: 0.0 - theta: 1.3047202586 - kappa: 4.8253438381e-06 - s: 46.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.907109 - y: 4140755.9796 - z: 0.0 - theta: 1.30472073958 - kappa: 4.79959763826e-06 - s: 46.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.933404 - y: 4140756.07608 - z: 0.0 - theta: 1.30472121893 - kappa: 4.76813983408e-06 - s: 46.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.959699 - y: 4140756.17257 - z: 0.0 - theta: 1.30472169267 - kappa: 4.72375327019e-06 - s: 46.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.985993 - y: 4140756.26905 - z: 0.0 - theta: 1.3047221626 - kappa: 4.67321715561e-06 - s: 46.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.012288 - y: 4140756.36553 - z: 0.0 - theta: 1.30472262815 - kappa: 4.61559460893e-06 - s: 46.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.038582 - y: 4140756.46201 - z: 0.0 - theta: 1.30472308487 - kappa: 4.54711610889e-06 - s: 46.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.064877 - y: 4140756.55849 - z: 0.0 - theta: 1.30472353701 - kappa: 4.47380048103e-06 - s: 46.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.091171 - y: 4140756.65497 - z: 0.0 - theta: 1.30472398008 - kappa: 4.39160593736e-06 - s: 47.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.117466 - y: 4140756.75145 - z: 0.0 - theta: 1.30472441392 - kappa: 4.30198643893e-06 - s: 47.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.14376 - y: 4140756.84793 - z: 0.0 - theta: 1.30472484207 - kappa: 4.2079016836e-06 - s: 47.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.170054 - y: 4140756.94441 - z: 0.0 - theta: 1.30472525518 - kappa: 4.10366841799e-06 - s: 47.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.196349 - y: 4140757.0409 - z: 0.0 - theta: 1.30472566043 - kappa: 3.99491829435e-06 - s: 47.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.222643 - y: 4140757.13738 - z: 0.0 - theta: 1.30472605602 - kappa: 3.88061564012e-06 - s: 47.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.248937 - y: 4140757.23386 - z: 0.0 - theta: 1.30472643547 - kappa: 3.75833605001e-06 - s: 47.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.275231 - y: 4140757.33034 - z: 0.0 - theta: 1.30472680699 - kappa: 3.63246565774e-06 - s: 47.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.301525 - y: 4140757.42682 - z: 0.0 - theta: 1.30472716293 - kappa: 3.49992415737e-06 - s: 47.8000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.327819 - y: 4140757.5233 - z: 0.0 - theta: 1.30472750488 - kappa: 3.3621627784e-06 - s: 47.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.354113 - y: 4140757.61978 - z: 0.0 - theta: 1.30472783808 - kappa: 3.22118245779e-06 - s: 48.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.354113 - y: 4140757.61978 - z: 0.0 - theta: 1.30472783808 - kappa: 3.22118245779e-06 - s: 48.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.380407 - y: 4140757.71626 - z: 0.0 - theta: 1.30472814894 - kappa: 3.07293533773e-06 - s: 48.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.406701 - y: 4140757.81274 - z: 0.0 - theta: 1.30472844928 - kappa: 2.9217024974e-06 - s: 48.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.432995 - y: 4140757.90923 - z: 0.0 - theta: 1.30472873581 - kappa: 2.76655252212e-06 - s: 48.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.459289 - y: 4140758.00571 - z: 0.0 - theta: 1.30472900129 - kappa: 2.60620304118e-06 - s: 48.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.485583 - y: 4140758.10219 - z: 0.0 - theta: 1.30472925648 - kappa: 2.44350905218e-06 - s: 48.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.511877 - y: 4140758.19867 - z: 0.0 - theta: 1.30472949129 - kappa: 2.2764532624e-06 - s: 48.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.538171 - y: 4140758.29515 - z: 0.0 - theta: 1.30472970916 - kappa: 2.10628108143e-06 - s: 48.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.564465 - y: 4140758.39163 - z: 0.0 - theta: 1.30472991623 - kappa: 1.93413624386e-06 - s: 48.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.590759 - y: 4140758.48811 - z: 0.0 - theta: 1.3047300959 - kappa: 1.75770782331e-06 - s: 48.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.617052 - y: 4140758.58459 - z: 0.0 - theta: 1.30473026367 - kappa: 1.57972323181e-06 - s: 49.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.643346 - y: 4140758.68108 - z: 0.0 - theta: 1.30473041475 - kappa: 1.39955843642e-06 - s: 49.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.66964 - y: 4140758.77756 - z: 0.0 - theta: 1.30473054212 - kappa: 1.21686995368e-06 - s: 49.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.695934 - y: 4140758.87404 - z: 0.0 - theta: 1.30473065785 - kappa: 1.03308323251e-06 - s: 49.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.722228 - y: 4140758.97052 - z: 0.0 - theta: 1.3047307502 - kappa: 8.47345559458e-07 - s: 49.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.748521 - y: 4140759.067 - z: 0.0 - theta: 1.30473082438 - kappa: 6.60493374046e-07 - s: 49.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.774815 - y: 4140759.16348 - z: 0.0 - theta: 1.30473088669 - kappa: 4.7291479603e-07 - s: 49.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.801109 - y: 4140759.25996 - z: 0.0 - theta: 1.30473091893 - kappa: 2.8413740378e-07 - s: 49.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.827403 - y: 4140759.35645 - z: 0.0 - theta: 1.30473093903 - kappa: 9.51317851071e-08 - s: 49.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.853696 - y: 4140759.45293 - z: 0.0 - theta: 1.30473094095 - kappa: -9.42155338476e-08 - s: 49.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.87999 - y: 4140759.54941 - z: 0.0 - theta: 1.30473091866 - kappa: -2.83512338554e-07 - s: 50.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.906284 - y: 4140759.64589 - z: 0.0 - theta: 1.30473088435 - kappa: -4.72661124329e-07 - s: 50.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.932577 - y: 4140759.74237 - z: 0.0 - theta: 1.30473082561 - kappa: -6.61248432264e-07 - s: 50.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.958871 - y: 4140759.83885 - z: 0.0 - theta: 1.30473074907 - kappa: -8.49049982942e-07 - s: 50.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.985165 - y: 4140759.93533 - z: 0.0 - theta: 1.30473066019 - kappa: -1.03630735289e-06 - s: 50.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.011459 - y: 4140760.03181 - z: 0.0 - theta: 1.30473054182 - kappa: -1.22162581185e-06 - s: 50.5000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.037752 - y: 4140760.1283 - z: 0.0 - theta: 1.30473041173 - kappa: -1.40592183957e-06 - s: 50.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.064046 - y: 4140760.22478 - z: 0.0 - theta: 1.30473026347 - kappa: -1.58861946491e-06 - s: 50.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.09034 - y: 4140760.32126 - z: 0.0 - theta: 1.30473009253 - kappa: -1.76879397505e-06 - s: 50.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.116634 - y: 4140760.41774 - z: 0.0 - theta: 1.30472991017 - kappa: -1.94757420665e-06 - s: 50.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.142928 - y: 4140760.51422 - z: 0.0 - theta: 1.30472970441 - kappa: -2.12317892394e-06 - s: 51.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.169222 - y: 4140760.6107 - z: 0.0 - theta: 1.30472948267 - kappa: -2.29619920645e-06 - s: 51.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.195515 - y: 4140760.70718 - z: 0.0 - theta: 1.3047292491 - kappa: -2.46730752984e-06 - s: 51.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.221809 - y: 4140760.80366 - z: 0.0 - theta: 1.30472898927 - kappa: -2.63343199697e-06 - s: 51.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.248103 - y: 4140760.90015 - z: 0.0 - theta: 1.30472871904 - kappa: -2.79728776349e-06 - s: 51.4000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.274397 - y: 4140760.99663 - z: 0.0 - theta: 1.30472843229 - kappa: -2.95750341383e-06 - s: 51.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.300691 - y: 4140761.09311 - z: 0.0 - theta: 1.30472812627 - kappa: -3.11282491847e-06 - s: 51.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.326985 - y: 4140761.18959 - z: 0.0 - theta: 1.30472781044 - kappa: -3.26550586867e-06 - s: 51.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.353279 - y: 4140761.28607 - z: 0.0 - theta: 1.3047274744 - kappa: -3.4122956507e-06 - s: 51.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.379573 - y: 4140761.38255 - z: 0.0 - theta: 1.30472712555 - kappa: -3.55480388292e-06 - s: 51.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.405868 - y: 4140761.47903 - z: 0.0 - theta: 1.30472676658 - kappa: -3.69393077768e-06 - s: 52.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.432162 - y: 4140761.57551 - z: 0.0 - theta: 1.30472638693 - kappa: -3.82513040605e-06 - s: 52.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.458456 - y: 4140761.672 - z: 0.0 - theta: 1.30472599918 - kappa: -3.95281504015e-06 - s: 52.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.48475 - y: 4140761.76848 - z: 0.0 - theta: 1.3047255983 - kappa: -4.07471624136e-06 - s: 52.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.511044 - y: 4140761.86496 - z: 0.0 - theta: 1.30472518334 - kappa: -4.18945379428e-06 - s: 52.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.537339 - y: 4140761.96144 - z: 0.0 - theta: 1.30472476116 - kappa: -4.30030448928e-06 - s: 52.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.563633 - y: 4140762.05792 - z: 0.0 - theta: 1.3047243243 - kappa: -4.40244675627e-06 - s: 52.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.589927 - y: 4140762.1544 - z: 0.0 - theta: 1.30472387901 - kappa: -4.49871187914e-06 - s: 52.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.616222 - y: 4140762.25088 - z: 0.0 - theta: 1.30472342662 - kappa: -4.5900247076e-06 - s: 52.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.642516 - y: 4140762.34736 - z: 0.0 - theta: 1.30472296134 - kappa: -4.67056834906e-06 - s: 52.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.668811 - y: 4140762.44384 - z: 0.0 - theta: 1.30472249125 - kappa: -4.74635067046e-06 - s: 53.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.695105 - y: 4140762.54033 - z: 0.0 - theta: 1.30472201329 - kappa: -4.81410466541e-06 - s: 53.1000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.7214 - y: 4140762.63681 - z: 0.0 - theta: 1.30472152812 - kappa: -4.87252699145e-06 - s: 53.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.747695 - y: 4140762.73329 - z: 0.0 - theta: 1.30472103931 - kappa: -4.9258161228e-06 - s: 53.3000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.773989 - y: 4140762.82977 - z: 0.0 - theta: 1.30472054374 - kappa: -4.96747799349e-06 - s: 53.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.800284 - y: 4140762.92625 - z: 0.0 - theta: 1.30472004525 - kappa: -5.00176860338e-06 - s: 53.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.826579 - y: 4140763.02273 - z: 0.0 - theta: 1.30471954412 - kappa: -5.02943442221e-06 - s: 53.6000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.852874 - y: 4140763.11921 - z: 0.0 - theta: 1.30471903997 - kappa: -5.04359057839e-06 - s: 53.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.879169 - y: 4140763.21569 - z: 0.0 - theta: 1.30471853529 - kappa: -5.05173905623e-06 - s: 53.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.905464 - y: 4140763.31217 - z: 0.0 - theta: 1.30471803002 - kappa: -5.0495127823e-06 - s: 53.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.931759 - y: 4140763.40865 - z: 0.0 - theta: 1.3047175259 - kappa: -5.0358882621e-06 - s: 54.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.958054 - y: 4140763.50514 - z: 0.0 - theta: 1.30471702273 - kappa: -5.01588417948e-06 - s: 54.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.984349 - y: 4140763.60162 - z: 0.0 - theta: 1.3047165233 - kappa: -4.98123248395e-06 - s: 54.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.010644 - y: 4140763.6981 - z: 0.0 - theta: 1.30471602741 - kappa: -4.93781685144e-06 - s: 54.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.036939 - y: 4140763.79458 - z: 0.0 - theta: 1.3047155349 - kappa: -4.88600244397e-06 - s: 54.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.063234 - y: 4140763.89106 - z: 0.0 - theta: 1.30471505122 - kappa: -4.8180393164e-06 - s: 54.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.08953 - y: 4140763.98754 - z: 0.0 - theta: 1.30471457228 - kappa: -4.74282212908e-06 - s: 54.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.115825 - y: 4140764.08402 - z: 0.0 - theta: 1.30471410212 - kappa: -4.65478229428e-06 - s: 54.7000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.14212 - y: 4140764.1805 - z: 0.0 - theta: 1.30471364293 - kappa: -4.55337905506e-06 - s: 54.8000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.168416 - y: 4140764.27698 - z: 0.0 - theta: 1.30471319024 - kappa: -4.44434986795e-06 - s: 54.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.194711 - y: 4140764.37346 - z: 0.0 - theta: 1.30471275446 - kappa: -4.31755127038e-06 - s: 55.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.221007 - y: 4140764.46994 - z: 0.0 - theta: 1.30471232954 - kappa: -4.18069747845e-06 - s: 55.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.247302 - y: 4140764.56642 - z: 0.0 - theta: 1.30471191571 - kappa: -4.03356950244e-06 - s: 55.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.273598 - y: 4140764.66291 - z: 0.0 - theta: 1.3047115244 - kappa: -3.86775516711e-06 - s: 55.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.299894 - y: 4140764.75939 - z: 0.0 - theta: 1.30471114409 - kappa: -3.69344038957e-06 - s: 55.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.326189 - y: 4140764.85587 - z: 0.0 - theta: 1.3047107842 - kappa: -3.50375367291e-06 - s: 55.5000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.352485 - y: 4140764.95235 - z: 0.0 - theta: 1.30471044634 - kappa: -3.2988398182e-06 - s: 55.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.378781 - y: 4140765.04883 - z: 0.0 - theta: 1.30471012156 - kappa: -3.08505363914e-06 - s: 55.7000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.405076 - y: 4140765.14531 - z: 0.0 - theta: 1.30470982964 - kappa: -2.85027489625e-06 - s: 55.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.431372 - y: 4140765.24179 - z: 0.0 - theta: 1.30470955664 - kappa: -2.60425112621e-06 - s: 55.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.457668 - y: 4140765.33827 - z: 0.0 - theta: 1.30470930424 - kappa: -2.34597640165e-06 - s: 56.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.457668 - y: 4140765.33827 - z: 0.0 - theta: 1.30470930424 - kappa: -2.34597640165e-06 - s: 56.0000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.483964 - y: 4140765.43475 - z: 0.0 - theta: 1.30470908977 - kappa: -2.06657914244e-06 - s: 56.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.51026 - y: 4140765.53123 - z: 0.0 - theta: 1.30470889356 - kappa: -1.77743509476e-06 - s: 56.2000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.536556 - y: 4140765.62771 - z: 0.0 - theta: 1.30470873175 - kappa: -1.47026849963e-06 - s: 56.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.562851 - y: 4140765.72419 - z: 0.0 - theta: 1.30470860423 - kappa: -1.14649317142e-06 - s: 56.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.589147 - y: 4140765.82067 - z: 0.0 - theta: 1.30470849721 - kappa: -8.14551911666e-07 - s: 56.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.615443 - y: 4140765.91715 - z: 0.0 - theta: 1.30470844032 - kappa: -4.83351772048e-07 - s: 56.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.641739 - y: 4140766.01364 - z: 0.0 - theta: 1.30470840745 - kappa: -1.58947237709e-07 - s: 56.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.668035 - y: 4140766.11012 - z: 0.0 - theta: 1.30470840248 - kappa: 1.57562109523e-07 - s: 56.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.694331 - y: 4140766.2066 - z: 0.0 - theta: 1.30470844012 - kappa: 4.6169426272e-07 - s: 56.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.720627 - y: 4140766.30308 - z: 0.0 - theta: 1.30470849685 - kappa: 7.601853431e-07 - s: 57.0000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.746923 - y: 4140766.39956 - z: 0.0 - theta: 1.30470858876 - kappa: 1.04817769638e-06 - s: 57.1000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.773219 - y: 4140766.49604 - z: 0.0 - theta: 1.3047087101 - kappa: 1.32714202448e-06 - s: 57.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.799514 - y: 4140766.59252 - z: 0.0 - theta: 1.3047088492 - kappa: 1.60063451042e-06 - s: 57.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.82581 - y: 4140766.689 - z: 0.0 - theta: 1.30470902904 - kappa: 1.86126269175e-06 - s: 57.4000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.852106 - y: 4140766.78548 - z: 0.0 - theta: 1.30470922706 - kappa: 2.11597407984e-06 - s: 57.5000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.878402 - y: 4140766.88196 - z: 0.0 - theta: 1.30470944762 - kappa: 2.36335249538e-06 - s: 57.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.904698 - y: 4140766.97844 - z: 0.0 - theta: 1.30470970074 - kappa: 2.59979973053e-06 - s: 57.7000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.930994 - y: 4140767.07492 - z: 0.0 - theta: 1.30470996869 - kappa: 2.8311730896e-06 - s: 57.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.957289 - y: 4140767.1714 - z: 0.0 - theta: 1.30471026443 - kappa: 3.05291663525e-06 - s: 57.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.983585 - y: 4140767.26788 - z: 0.0 - theta: 1.30471058217 - kappa: 3.26677152926e-06 - s: 58.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.009881 - y: 4140767.36437 - z: 0.0 - theta: 1.30471091356 - kappa: 3.47572179144e-06 - s: 58.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.036176 - y: 4140767.46085 - z: 0.0 - theta: 1.30471127644 - kappa: 3.67298337125e-06 - s: 58.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.062472 - y: 4140767.55733 - z: 0.0 - theta: 1.30471165252 - kappa: 3.86516087258e-06 - s: 58.3000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.088768 - y: 4140767.65381 - z: 0.0 - theta: 1.30471204608 - kappa: 4.0506138161e-06 - s: 58.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.115063 - y: 4140767.75029 - z: 0.0 - theta: 1.30471246346 - kappa: 4.2265355304e-06 - s: 58.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.141359 - y: 4140767.84677 - z: 0.0 - theta: 1.30471289187 - kappa: 4.39795060221e-06 - s: 58.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.167654 - y: 4140767.94325 - z: 0.0 - theta: 1.30471334121 - kappa: 4.56065097752e-06 - s: 58.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.193949 - y: 4140768.03973 - z: 0.0 - theta: 1.30471380619 - kappa: 4.71655598593e-06 - s: 58.8000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.220245 - y: 4140768.13621 - z: 0.0 - theta: 1.30471428115 - kappa: 4.86812360373e-06 - s: 58.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.24654 - y: 4140768.23269 - z: 0.0 - theta: 1.30471477916 - kappa: 5.00922436436e-06 - s: 59.0000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.272835 - y: 4140768.32917 - z: 0.0 - theta: 1.30471528621 - kappa: 5.14602765126e-06 - s: 59.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.299131 - y: 4140768.42565 - z: 0.0 - theta: 1.30471580601 - kappa: 5.27676096631e-06 - s: 59.2000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.325426 - y: 4140768.52214 - z: 0.0 - theta: 1.30471634215 - kappa: 5.39931691251e-06 - s: 59.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.351721 - y: 4140768.61862 - z: 0.0 - theta: 1.30471688596 - kappa: 5.51793346944e-06 - s: 59.4000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.378016 - y: 4140768.7151 - z: 0.0 - theta: 1.30471744447 - kappa: 5.62879662142e-06 - s: 59.5000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.404311 - y: 4140768.81158 - z: 0.0 - theta: 1.30471801326 - kappa: 5.73391157899e-06 - s: 59.6000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.430606 - y: 4140768.90806 - z: 0.0 - theta: 1.30471858879 - kappa: 5.83525640215e-06 - s: 59.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.456901 - y: 4140769.00454 - z: 0.0 - theta: 1.30471917981 - kappa: 5.92740236922e-06 - s: 59.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.483196 - y: 4140769.10102 - z: 0.0 - theta: 1.30471977643 - kappa: 6.01599133798e-06 - s: 59.9000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.50949 - y: 4140769.1975 - z: 0.0 - theta: 1.3047203815 - kappa: 6.09921108036e-06 - s: 60.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.535785 - y: 4140769.29398 - z: 0.0 - theta: 1.30472099663 - kappa: 6.17556119043e-06 - s: 60.1000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.56208 - y: 4140769.39046 - z: 0.0 - theta: 1.30472161651 - kappa: 6.24853917098e-06 - s: 60.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.588374 - y: 4140769.48695 - z: 0.0 - theta: 1.30472224551 - kappa: 6.31477120169e-06 - s: 60.3000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.614669 - y: 4140769.58343 - z: 0.0 - theta: 1.30472288038 - kappa: 6.37625607005e-06 - s: 60.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.640963 - y: 4140769.67991 - z: 0.0 - theta: 1.30472351935 - kappa: 6.43442661377e-06 - s: 60.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.667258 - y: 4140769.77639 - z: 0.0 - theta: 1.30472416689 - kappa: 6.48493536571e-06 - s: 60.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.693552 - y: 4140769.87287 - z: 0.0 - theta: 1.30472481742 - kappa: 6.53246999204e-06 - s: 60.7000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.719846 - y: 4140769.96935 - z: 0.0 - theta: 1.30472547256 - kappa: 6.57538229907e-06 - s: 60.8000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.746141 - y: 4140770.06583 - z: 0.0 - theta: 1.30472613262 - kappa: 6.61268655343e-06 - s: 60.9000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.772435 - y: 4140770.16231 - z: 0.0 - theta: 1.30472679497 - kappa: 6.64718593488e-06 - s: 61.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.798729 - y: 4140770.25879 - z: 0.0 - theta: 1.30472746158 - kappa: 6.67599298627e-06 - s: 61.1000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.825023 - y: 4140770.35528 - z: 0.0 - theta: 1.30472813053 - kappa: 6.70100773747e-06 - s: 61.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.851317 - y: 4140770.45176 - z: 0.0 - theta: 1.30472880123 - kappa: 6.72319452778e-06 - s: 61.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.877611 - y: 4140770.54824 - z: 0.0 - theta: 1.30472947487 - kappa: 6.73924164036e-06 - s: 61.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.903905 - y: 4140770.64472 - z: 0.0 - theta: 1.30473014937 - kappa: 6.75288187843e-06 - s: 61.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.930198 - y: 4140770.7412 - z: 0.0 - theta: 1.30473082516 - kappa: 6.76269287724e-06 - s: 61.6000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.956492 - y: 4140770.83768 - z: 0.0 - theta: 1.3047315018 - kappa: 6.76811121247e-06 - s: 61.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.982786 - y: 4140770.93416 - z: 0.0 - theta: 1.30473217873 - kappa: 6.77129192212e-06 - s: 61.8000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.009079 - y: 4140771.03064 - z: 0.0 - theta: 1.30473285584 - kappa: 6.76988009899e-06 - s: 61.9000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.035373 - y: 4140771.12713 - z: 0.0 - theta: 1.30473353259 - kappa: 6.76558463722e-06 - s: 62.0000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.061666 - y: 4140771.22361 - z: 0.0 - theta: 1.30473420906 - kappa: 6.75899376477e-06 - s: 62.1000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.08796 - y: 4140771.32009 - z: 0.0 - theta: 1.30473488414 - kappa: 6.74773911553e-06 - s: 62.2000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.114253 - y: 4140771.41657 - z: 0.0 - theta: 1.30473555837 - kappa: 6.73464483086e-06 - s: 62.3000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.140546 - y: 4140771.51305 - z: 0.0 - theta: 1.30473623117 - kappa: 6.71856057889e-06 - s: 62.4000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.166839 - y: 4140771.60953 - z: 0.0 - theta: 1.30473690178 - kappa: 6.69925283002e-06 - s: 62.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.193133 - y: 4140771.70601 - z: 0.0 - theta: 1.30473757114 - kappa: 6.67827468995e-06 - s: 62.6000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.219426 - y: 4140771.8025 - z: 0.0 - theta: 1.30473823741 - kappa: 6.65385001133e-06 - s: 62.7000291884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.245719 - y: 4140771.89898 - z: 0.0 - theta: 1.3047389014 - kappa: 6.62740412515e-06 - s: 62.8000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.272012 - y: 4140771.99546 - z: 0.0 - theta: 1.30473956345 - kappa: 6.59924158834e-06 - s: 62.9000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.298304 - y: 4140772.09194 - z: 0.0 - theta: 1.30474022101 - kappa: 6.56784493076e-06 - s: 63.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.324597 - y: 4140772.18842 - z: 0.0 - theta: 1.30474087649 - kappa: 6.53517586262e-06 - s: 63.1000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.35089 - y: 4140772.2849 - z: 0.0 - theta: 1.30474152842 - kappa: 6.50040231475e-06 - s: 63.2000291886 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.377183 - y: 4140772.38139 - z: 0.0 - theta: 1.30474217611 - kappa: 6.46352818449e-06 - s: 63.3000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.403475 - y: 4140772.47787 - z: 0.0 - theta: 1.30474282143 - kappa: 6.42555088297e-06 - s: 63.4000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.429768 - y: 4140772.57435 - z: 0.0 - theta: 1.30474346131 - kappa: 6.38531925841e-06 - s: 63.5000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.45606 - y: 4140772.67083 - z: 0.0 - theta: 1.3047440977 - kappa: 6.34388259849e-06 - s: 63.6000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.482353 - y: 4140772.76731 - z: 0.0 - theta: 1.30474473094 - kappa: 6.30135428371e-06 - s: 63.7000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.508645 - y: 4140772.86379 - z: 0.0 - theta: 1.30474535775 - kappa: 6.25697523102e-06 - s: 63.8000291885 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.534937 - y: 4140772.96027 - z: 0.0 - theta: 1.30474598169 - kappa: 6.21189097801e-06 - s: 63.9000291882 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.56123 - y: 4140773.05676 - z: 0.0 - theta: 1.30474660066 - kappa: 6.16563397453e-06 - s: 64.0000291883 - dkappa: 0.0 - ddkappa: 0.0 - } - } - path { - name: "QP_SPLINE_PATH_OPTIMIZER" - path_point { - x: 586347.749165 - y: 4140711.30439 - z: 0.0 - theta: 1.3169659463 - kappa: 0.000137228886317 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586347.924108 - y: 4140711.97851 - z: 0.0 - theta: 1.31667913555 - kappa: -0.000913971555126 - s: 0.696450286174 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.099469 - y: 4140712.65251 - z: 0.0 - theta: 1.31575508834 - kappa: -0.00169717537066 - s: 1.39289505007 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.275615 - y: 4140713.32631 - z: 0.0 - theta: 1.31437130704 - kappa: -0.00223861666045 - s: 2.08933048068 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.452799 - y: 4140713.99981 - z: 0.0 - theta: 1.31268706378 - kappa: -0.00256450765109 - s: 2.78575521416 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.631176 - y: 4140714.673 - z: 0.0 - theta: 1.31084334268 - kappa: -0.0027006798391 - s: 3.48216989903 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.810811 - y: 4140715.34584 - z: 0.0 - theta: 1.30896406783 - kappa: -0.00267080624305 - s: 4.17857650677 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586348.99169 - y: 4140716.01834 - z: 0.0 - theta: 1.30715604816 - kappa: -0.00250045765395 - s: 4.87497761392 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.173734 - y: 4140716.69052 - z: 0.0 - theta: 1.30550801122 - kappa: -0.00221561031576 - s: 5.57137579462 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.356811 - y: 4140717.36242 - z: 0.0 - theta: 1.30409068448 - kappa: -0.00184226538842 - s: 6.26777316805 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.540748 - y: 4140718.03409 - z: 0.0 - theta: 1.30295663242 - kappa: -0.00140641690472 - s: 6.96417114567 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.725342 - y: 4140718.70558 - z: 0.0 - theta: 1.30214030781 - kappa: -0.000934051234022 - s: 7.66057036294 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586349.910372 - y: 4140719.37695 - z: 0.0 - theta: 1.30165812203 - kappa: -0.000451160346554 - s: 8.35697077733 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.095614 - y: 4140720.04826 - z: 0.0 - theta: 1.30150835018 - kappa: 1.6277872107e-05 - s: 9.05337188422 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.28085 - y: 4140720.71957 - z: 0.0 - theta: 1.30167117695 - kappa: 0.000442289162308 - s: 9.74977298177 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.465882 - y: 4140721.39094 - z: 0.0 - theta: 1.30210871906 - kappa: 0.000800888793734 - s: 10.4461734378 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.650543 - y: 4140722.06241 - z: 0.0 - theta: 1.30276497784 - kappa: 0.0010660974122 - s: 11.1425728884 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586350.834709 - y: 4140722.73402 - z: 0.0 - theta: 1.30356586701 - kappa: 0.0012119322393 - s: 11.8389713338 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.018314 - y: 4140723.40578 - z: 0.0 - theta: 1.30441920737 - kappa: 0.00121240304887 - s: 12.5353690992 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.201359 - y: 4140724.07769 - z: 0.0 - theta: 1.30521472151 - kappa: 0.00104152975263 - s: 13.2317666776 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.383924 - y: 4140724.74973 - z: 0.0 - theta: 1.3058240428 - kappa: 0.00067346715298 - s: 13.9281644832 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.566175 - y: 4140725.42186 - z: 0.0 - theta: 1.30614246603 - kappa: 0.000257515118755 - s: 14.6245626301 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.748302 - y: 4140726.09402 - z: 0.0 - theta: 1.30620465075 - kappa: -6.39052754116e-05 - s: 15.3209609491 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586351.930456 - y: 4140726.76617 - z: 0.0 - theta: 1.30607336575 - kappa: -0.000299588745038 - s: 16.0173592139 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.112747 - y: 4140727.43829 - z: 0.0 - theta: 1.30580523547 - kappa: -0.000458408340308 - s: 16.7137572672 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.295249 - y: 4140728.11035 - z: 0.0 - theta: 1.30545048565 - kappa: -0.000549967859452 - s: 17.4101550578 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.478007 - y: 4140728.78233 - z: 0.0 - theta: 1.30505278074 - kappa: -0.0005832224994 - s: 18.1065526366 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.661036 - y: 4140729.45425 - z: 0.0 - theta: 1.30464969201 - kappa: -0.000566871165575 - s: 18.8029501089 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586352.844328 - y: 4140730.12609 - z: 0.0 - theta: 1.30427273664 - kappa: -0.000509624013845 - s: 19.4993475957 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.027858 - y: 4140730.79787 - z: 0.0 - theta: 1.30394736386 - kappa: -0.00042017956153 - s: 20.1957451942 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.211583 - y: 4140731.4696 - z: 0.0 - theta: 1.30369296903 - kappa: -0.000307239736219 - s: 20.8921429579 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.395451 - y: 4140732.14128 - z: 0.0 - theta: 1.30352287407 - kappa: -0.000179511770554 - s: 21.5885408862 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.579403 - y: 4140732.81295 - z: 0.0 - theta: 1.30344435571 - kappa: -4.56952787563e-05 - s: 22.2849389325 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.763377 - y: 4140733.4846 - z: 0.0 - theta: 1.30345862716 - kappa: 8.55064213149e-05 - s: 22.9813370207 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586353.947311 - y: 4140734.15627 - z: 0.0 - theta: 1.30356082192 - kappa: 0.000205390233095 - s: 23.6777350695 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.13115 - y: 4140734.82797 - z: 0.0 - theta: 1.30374004165 - kappa: 0.000305253609853 - s: 24.3741330132 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.314847 - y: 4140735.4997 - z: 0.0 - theta: 1.30397931402 - kappa: 0.000376392192362 - s: 25.0705308203 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.49837 - y: 4140736.17148 - z: 0.0 - theta: 1.3042555932 - kappa: 0.0004101073408 - s: 25.7669284974 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.681702 - y: 4140736.84331 - z: 0.0 - theta: 1.30453979741 - kappa: 0.000397691638284 - s: 26.4633260859 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586354.86485 - y: 4140737.5152 - z: 0.0 - theta: 1.30479676757 - kappa: 0.000330441459813 - s: 27.1597236398 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.047846 - y: 4140738.18712 - z: 0.0 - theta: 1.30498529228 - kappa: 0.000199841248603 - s: 27.856121204 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.230749 - y: 4140738.85907 - z: 0.0 - theta: 1.30507322512 - kappa: 5.85928171085e-05 - s: 28.5525187887 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.413624 - y: 4140739.53103 - z: 0.0 - theta: 1.30507474971 - kappa: -4.88179682015e-05 - s: 29.2489163761 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.59652 - y: 4140740.20298 - z: 0.0 - theta: 1.30501237731 - kappa: -0.000125497677579 - s: 29.9453139418 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.779473 - y: 4140740.87491 - z: 0.0 - theta: 1.3049061122 - kappa: -0.00017559441527 - s: 30.6417114728 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586355.962508 - y: 4140741.54683 - z: 0.0 - theta: 1.30477314326 - kappa: -0.000202697973503 - s: 31.3381089746 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.145637 - y: 4140742.21872 - z: 0.0 - theta: 1.30462841835 - kappa: -0.000209882009923 - s: 32.0345064637 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.328863 - y: 4140742.89058 - z: 0.0 - theta: 1.30448473656 - kappa: -0.000200207188148 - s: 32.7309039578 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.512183 - y: 4140743.56241 - z: 0.0 - theta: 1.30435277109 - kappa: -0.000176746145847 - s: 33.4273014767 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.695585 - y: 4140744.23423 - z: 0.0 - theta: 1.30424105125 - kappa: -0.000142569024815 - s: 34.123699032 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586356.879053 - y: 4140744.90602 - z: 0.0 - theta: 1.30415597798 - kappa: -0.000100740681164 - s: 34.8200966276 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.062568 - y: 4140745.5778 - z: 0.0 - theta: 1.30410180541 - kappa: -5.43322693088e-05 - s: 35.5164942595 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.246109 - y: 4140746.24958 - z: 0.0 - theta: 1.30408065277 - kappa: -6.41207535406e-06 - s: 36.212891917 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.429652 - y: 4140746.92135 - z: 0.0 - theta: 1.30409251347 - kappa: 3.99517413093e-05 - s: 36.9092895844 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.613177 - y: 4140747.59313 - z: 0.0 - theta: 1.30413522615 - kappa: 8.16903729218e-05 - s: 37.6056872465 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.796665 - y: 4140748.26492 - z: 0.0 - theta: 1.30420450315 - kappa: 0.000115735671446 - s: 38.3020848918 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586357.980098 - y: 4140748.93673 - z: 0.0 - theta: 1.30429392364 - kappa: 0.000139016997048 - s: 38.9984825114 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.163467 - y: 4140749.60855 - z: 0.0 - theta: 1.30439491695 - kappa: 0.000148468713193 - s: 39.6948801045 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.346767 - y: 4140750.28039 - z: 0.0 - theta: 1.30449678639 - kappa: 0.000141021095574 - s: 40.3912776741 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.530002 - y: 4140750.95225 - z: 0.0 - theta: 1.30458669278 - kappa: 0.000113601885354 - s: 41.0876752281 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.713185 - y: 4140751.62413 - z: 0.0 - theta: 1.30464966815 - kappa: 6.3302563182e-05 - s: 41.7840727707 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586358.896338 - y: 4140752.29601 - z: 0.0 - theta: 1.30467478985 - kappa: 1.12781688462e-05 - s: 42.480470306 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.079485 - y: 4140752.96789 - z: 0.0 - theta: 1.30466861923 - kappa: -2.67511975516e-05 - s: 43.1768678324 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.262644 - y: 4140753.63977 - z: 0.0 - theta: 1.30464027083 - kappa: -5.29248621053e-05 - s: 43.8732653487 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.445828 - y: 4140754.31164 - z: 0.0 - theta: 1.30459721119 - kappa: -6.9195341814e-05 - s: 44.5696628585 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.629044 - y: 4140754.98351 - z: 0.0 - theta: 1.30454590554 - kappa: -7.68016181973e-05 - s: 45.2660603675 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.812295 - y: 4140755.65536 - z: 0.0 - theta: 1.3044919608 - kappa: -7.69920341223e-05 - s: 45.9624578813 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586359.995582 - y: 4140756.32721 - z: 0.0 - theta: 1.30444010829 - kappa: -7.09973177789e-05 - s: 46.6588554045 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.178902 - y: 4140756.99904 - z: 0.0 - theta: 1.30439422689 - kappa: -6.00569927439e-05 - s: 47.3552529402 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.36225 - y: 4140757.67087 - z: 0.0 - theta: 1.30435731859 - kappa: -4.54156687232e-05 - s: 48.0516504902 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.54562 - y: 4140758.34269 - z: 0.0 - theta: 1.3043315416 - kappa: -2.83068846955e-05 - s: 48.7480480527 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.729002 - y: 4140759.01451 - z: 0.0 - theta: 1.30431818233 - kappa: -9.9711852075e-06 - s: 49.4444456263 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586360.912389 - y: 4140759.68633 - z: 0.0 - theta: 1.30431765006 - kappa: 8.35165281891e-06 - s: 50.1408432065 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.095772 - y: 4140760.35815 - z: 0.0 - theta: 1.3043295198 - kappa: 2.54233574648e-05 - s: 50.8372407891 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.279144 - y: 4140761.02997 - z: 0.0 - theta: 1.30435248522 - kappa: 4.00040984049e-05 - s: 51.5336383697 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.462497 - y: 4140761.7018 - z: 0.0 - theta: 1.30438437207 - kappa: 5.08573126791e-05 - s: 52.2300359461 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.645826 - y: 4140762.37363 - z: 0.0 - theta: 1.30442216251 - kappa: 5.67407899576e-05 - s: 52.9264335145 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586361.829129 - y: 4140763.04547 - z: 0.0 - theta: 1.3044619606 - kappa: 5.64162540686e-05 - s: 53.6228310747 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.012406 - y: 4140763.71732 - z: 0.0 - theta: 1.30449901241 - kappa: 4.86487045938e-05 - s: 54.3192286269 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.19566 - y: 4140764.38917 - z: 0.0 - theta: 1.30452770036 - kappa: 3.21928220939e-05 - s: 55.0156261726 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.3789 - y: 4140765.06103 - z: 0.0 - theta: 1.30454154826 - kappa: 5.95449610329e-06 - s: 55.7120237127 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.562137 - y: 4140765.73289 - z: 0.0 - theta: 1.30453667854 - kappa: -1.8305591217e-05 - s: 56.4084212477 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.745382 - y: 4140766.40474 - z: 0.0 - theta: 1.30451812724 - kappa: -3.36637389276e-05 - s: 57.1048187805 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586362.928643 - y: 4140767.07659 - z: 0.0 - theta: 1.30449146888 - kappa: -4.17673611854e-05 - s: 57.8012163115 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.111922 - y: 4140767.74844 - z: 0.0 - theta: 1.30446141467 - kappa: -4.35871451425e-05 - s: 58.4976138455 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.295222 - y: 4140768.42028 - z: 0.0 - theta: 1.30443199908 - kappa: -4.00778020743e-05 - s: 59.1940113835 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.478541 - y: 4140769.09212 - z: 0.0 - theta: 1.3044066062 - kappa: -3.22008859906e-05 - s: 59.8904089265 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.661875 - y: 4140769.76395 - z: 0.0 - theta: 1.30438794246 - kappa: -2.09138450222e-05 - s: 60.5868064751 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586363.845218 - y: 4140770.43578 - z: 0.0 - theta: 1.30437804755 - kappa: -7.17302324371e-06 - s: 61.2832040292 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.028564 - y: 4140771.10761 - z: 0.0 - theta: 1.3043782978 - kappa: 8.06089196068e-06 - s: 61.9796015862 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.211907 - y: 4140771.77944 - z: 0.0 - theta: 1.30438939903 - kappa: 2.38308454745e-05 - s: 62.6759991445 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.395239 - y: 4140772.45127 - z: 0.0 - theta: 1.30441139206 - kappa: 3.91792350333e-05 - s: 63.372396701 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.578552 - y: 4140773.12311 - z: 0.0 - theta: 1.30444364712 - kappa: 5.31466138471e-05 - s: 64.0687942534 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.76184 - y: 4140773.79495 - z: 0.0 - theta: 1.30448487066 - kappa: 6.47755641534e-05 - s: 64.7651918001 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586364.945099 - y: 4140774.46681 - z: 0.0 - theta: 1.30453310172 - kappa: 7.31075998682e-05 - s: 65.46158934 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586365.128323 - y: 4140775.13867 - z: 0.0 - theta: 1.30458570729 - kappa: 7.71848892795e-05 - s: 66.1579868735 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586365.311511 - y: 4140775.81054 - z: 0.0 - theta: 1.30463939328 - kappa: 7.60488997358e-05 - s: 66.8543844013 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586365.494665 - y: 4140776.48242 - z: 0.0 - theta: 1.30469019529 - kappa: 6.87406386184e-05 - s: 67.5507819256 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586365.677786 - y: 4140777.15431 - z: 0.0 - theta: 1.30473348099 - kappa: 5.43042668251e-05 - s: 68.2471794471 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586365.860882 - y: 4140777.82621 - z: 0.0 - theta: 1.30476395238 - kappa: 3.17793876559e-05 - s: 68.9435769686 - dkappa: 0.0 - ddkappa: 0.0 - } - path_point { - x: 586366.043963 - y: 4140778.49811 - z: 0.0 - theta: 1.304775641 - kappa: 2.06878599753e-07 - s: 69.6399744892 - dkappa: 0.0 - ddkappa: 0.0 - } - } - path { - name: "planning_reference_line" - path_point { - x: 586345.049096 - y: 4140701.46759 - theta: 1.30473084017 - kappa: -3.2182808336e-05 - dkappa: -8.19943720429e-06 - } - path_point { - x: 586345.091258 - y: 4140701.6223 - theta: 1.30472557818 - kappa: -3.34254135259e-05 - dkappa: -7.30304170597e-06 - } - path_point { - x: 586345.13342 - y: 4140701.777 - theta: 1.30472012839 - kappa: -3.45260223107e-05 - dkappa: -6.42838365307e-06 - } - path_point { - x: 586345.175584 - y: 4140701.93171 - theta: 1.30471451329 - kappa: -3.54881212016e-05 - dkappa: -5.57546298234e-06 - } - path_point { - x: 586345.217748 - y: 4140702.08641 - theta: 1.30470875481 - kappa: -3.6315196696e-05 - dkappa: -4.74427980979e-06 - } - path_point { - x: 586345.259912 - y: 4140702.24111 - theta: 1.30470287433 - kappa: -3.70107353018e-05 - dkappa: -3.93483441923e-06 - } - path_point { - x: 586345.302078 - y: 4140702.39582 - theta: 1.30469689266 - kappa: -3.75782235605e-05 - dkappa: -3.14712725094e-06 - } - path_point { - x: 586345.344244 - y: 4140702.55052 - theta: 1.30469083005 - kappa: -3.80211480682e-05 - dkappa: -2.38115889076e-06 - } - path_point { - x: 586345.386411 - y: 4140702.70522 - theta: 1.30468470619 - kappa: -3.83429954955e-05 - dkappa: -1.63693005932e-06 - } - path_point { - x: 586345.428579 - y: 4140702.85992 - theta: 1.30467854023 - kappa: -3.85472526058e-05 - dkappa: -9.14441601576e-07 - } - path_point { - x: 586345.470748 - y: 4140703.01461 - theta: 1.30467235073 - kappa: -3.86374062719e-05 - dkappa: -2.1369447667e-07 - } - path_point { - x: 586345.512917 - y: 4140703.16931 - theta: 1.30466615572 - kappa: -3.86169434918e-05 - dkappa: 4.65310252032e-07 - } - path_point { - x: 586345.555087 - y: 4140703.32401 - theta: 1.30465997265 - kappa: -3.84893514022e-05 - dkappa: 1.12257142658e-06 - } - path_point { - x: 586345.597258 - y: 4140703.4787 - theta: 1.30465381841 - kappa: -3.82581172919e-05 - dkappa: 1.7580878038e-06 - } - path_point { - x: 586345.63943 - y: 4140703.6334 - theta: 1.30464770935 - kappa: -3.79267286125e-05 - dkappa: 2.37185806447e-06 - } - path_point { - x: 586345.681603 - y: 4140703.78809 - theta: 1.30464166124 - kappa: -3.74986729892e-05 - dkappa: 2.9638808221e-06 - } - path_point { - x: 586345.723776 - y: 4140703.94279 - theta: 1.30463568931 - kappa: -3.69774382294e-05 - dkappa: 3.53415463156e-06 - } - path_point { - x: 586345.76595 - y: 4140704.09748 - theta: 1.30462980821 - kappa: -3.63665123305e-05 - dkappa: 4.08267799737e-06 - } - path_point { - x: 586345.808125 - y: 4140704.25217 - theta: 1.30462403204 - kappa: -3.56693834866e-05 - dkappa: 4.60944938176e-06 - } - path_point { - x: 586345.850301 - y: 4140704.40686 - theta: 1.30461837435 - kappa: -3.48895400942e-05 - dkappa: 5.11446721241e-06 - } - path_point { - x: 586345.892477 - y: 4140704.56155 - theta: 1.30461284811 - kappa: -3.4030470756e-05 - dkappa: 5.59772989001e-06 - } - path_point { - x: 586345.934654 - y: 4140704.71624 - theta: 1.30460746576 - kappa: -3.30956642853e-05 - dkappa: 6.05923579549e-06 - } - path_point { - x: 586345.976832 - y: 4140704.87093 - theta: 1.30460223914 - kappa: -3.20886097075e-05 - dkappa: 6.49898329693e-06 - } - path_point { - x: 586346.01901 - y: 4140705.02562 - theta: 1.30459717957 - kappa: -3.10127962623e-05 - dkappa: 6.91697075638e-06 - } - path_point { - x: 586346.061189 - y: 4140705.1803 - theta: 1.30459229778 - kappa: -2.98717134038e-05 - dkappa: 7.31319653617e-06 - } - path_point { - x: 586346.103369 - y: 4140705.33499 - theta: 1.30458760396 - kappa: -2.86688508004e-05 - dkappa: 7.68765900519e-06 - } - path_point { - x: 586346.145549 - y: 4140705.48967 - theta: 1.30458310774 - kappa: -2.74076983335e-05 - dkappa: 8.04035654472e-06 - } - path_point { - x: 586346.187729 - y: 4140705.64436 - theta: 1.30457881818 - kappa: -2.60917460957e-05 - dkappa: 8.37128755411e-06 - } - path_point { - x: 586346.229911 - y: 4140705.79904 - theta: 1.30457474378 - kappa: -2.47244843879e-05 - dkappa: 8.68045045611e-06 - } - path_point { - x: 586346.272092 - y: 4140705.95373 - theta: 1.30457089249 - kappa: -2.33094037161e-05 - dkappa: 8.96784370201e-06 - } - path_point { - x: 586346.314274 - y: 4140706.10841 - theta: 1.30456727169 - kappa: -2.18499947867e-05 - dkappa: 9.23346577647e-06 - } - path_point { - x: 586346.356457 - y: 4140706.26309 - theta: 1.30456388821 - kappa: -2.03497485026e-05 - dkappa: 9.47731520205e-06 - } - path_point { - x: 586346.39864 - y: 4140706.41777 - theta: 1.30456074832 - kappa: -1.88121559567e-05 - dkappa: 9.69939054355e-06 - } - path_point { - x: 586346.440823 - y: 4140706.57245 - theta: 1.30455785772 - kappa: -1.72407084268e-05 - dkappa: 9.89969041206e-06 - } - path_point { - x: 586346.483006 - y: 4140706.72713 - theta: 1.30455522156 - kappa: -1.56388973686e-05 - dkappa: 1.00782134687e-05 - } - path_point { - x: 586346.52519 - y: 4140706.88181 - theta: 1.30455284442 - kappa: -1.40102144087e-05 - dkappa: 1.0234958428e-05 - } - path_point { - x: 586346.567374 - y: 4140707.03649 - theta: 1.30455073033 - kappa: -1.2358151337e-05 - dkappa: 1.03699240616e-05 - } - path_point { - x: 586346.609558 - y: 4140707.19117 - theta: 1.30454888277 - kappa: -1.06862000991e-05 - dkappa: 1.04831092004e-05 - } - path_point { - x: 586346.651743 - y: 4140707.34585 - theta: 1.30454730462 - kappa: -8.99785278751e-06 - dkappa: 1.05745127383e-05 - } - path_point { - x: 586346.693927 - y: 4140707.50053 - theta: 1.30454599826 - kappa: -7.29660163338e-06 - dkappa: 1.06441336336e-05 - } - path_point { - x: 586346.736111 - y: 4140707.6552 - theta: 1.30454496545 - kappa: -5.58593899711e-06 - dkappa: 1.0691970912e-05 - } - path_point { - x: 586346.778296 - y: 4140707.80988 - theta: 1.30454420743 - kappa: -3.86935735924e-06 - dkappa: 1.0718023668e-05 - } - path_point { - x: 586346.820481 - y: 4140707.96456 - theta: 1.30454372486 - kappa: -2.15034931091e-06 - dkappa: 1.07222910667e-05 - } - path_point { - x: 586346.862665 - y: 4140708.11923 - theta: 1.30454351786 - kappa: -4.32407544056e-07 - dkappa: 1.07047723454e-05 - } - path_point { - x: 586346.904849 - y: 4140708.27391 - theta: 1.30454358596 - kappa: 1.28097515848e-06 - dkappa: 1.06654668143e-05 - } - path_point { - x: 586346.947034 - y: 4140708.42858 - theta: 1.30454392817 - kappa: 2.98630593302e-06 - dkappa: 1.06043738575e-05 - } - path_point { - x: 586346.989218 - y: 4140708.58326 - theta: 1.3045445429 - kappa: 4.68009184515e-06 - dkappa: 1.05214929339e-05 - } - path_point { - x: 586347.031402 - y: 4140708.73793 - theta: 1.30454542803 - kappa: 6.35883989997e-06 - dkappa: 1.0416823577e-05 - } - path_point { - x: 586347.073585 - y: 4140708.89261 - theta: 1.30454658086 - kappa: 8.0190570523e-06 - dkappa: 1.02903653952e-05 - } - path_point { - x: 586347.115769 - y: 4140709.04728 - theta: 1.30454799814 - kappa: 9.65725021689e-06 - dkappa: 1.01421180716e-05 - } - path_point { - x: 586347.157952 - y: 4140709.20196 - theta: 1.30454967606 - kappa: 1.12699262786e-05 - dkappa: 9.97208136345e-06 - } - path_point { - x: 586347.200135 - y: 4140709.35663 - theta: 1.30455161024 - kappa: 1.28535921022e-05 - dkappa: 9.78025510153e-06 - } - path_point { - x: 586347.242317 - y: 4140709.5113 - theta: 1.30455379576 - kappa: 1.4404754543e-05 - dkappa: 9.56663918891e-06 - } - path_point { - x: 586347.284499 - y: 4140709.66598 - theta: 1.30455622713 - kappa: 1.59199204556e-05 - dkappa: 9.33123359981e-06 - } - path_point { - x: 586347.32668 - y: 4140709.82065 - theta: 1.30455889828 - kappa: 1.73955967043e-05 - dkappa: 9.074038378e-06 - } - path_point { - x: 586347.368861 - y: 4140709.97532 - theta: 1.30456180262 - kappa: 1.88282901721e-05 - dkappa: 8.79505363504e-06 - } - path_point { - x: 586347.411042 - y: 4140710.13 - theta: 1.30456493297 - kappa: 2.02145077696e-05 - dkappa: 8.49427954809e-06 - } - path_point { - x: 586347.453222 - y: 4140710.28467 - theta: 1.30456828159 - kappa: 2.1550756444e-05 - dkappa: 8.17171635768e-06 - } - path_point { - x: 586347.495401 - y: 4140710.43934 - theta: 1.3045718402 - kappa: 2.28335431872e-05 - dkappa: 7.82736436498e-06 - } - path_point { - x: 586347.53758 - y: 4140710.59402 - theta: 1.30457559994 - kappa: 2.40593750441e-05 - dkappa: 7.46122392897e-06 - } - path_point { - x: 586347.579758 - y: 4140710.74869 - theta: 1.30457955141 - kappa: 2.52247591198e-05 - dkappa: 7.07329546329e-06 - } - path_point { - x: 586347.621935 - y: 4140710.90336 - theta: 1.30458368463 - kappa: 2.63262025869e-05 - dkappa: 6.66357943279e-06 - } - path_point { - x: 586347.664112 - y: 4140711.05804 - theta: 1.30458798907 - kappa: 2.7360212692e-05 - dkappa: 6.23207634984e-06 - } - path_point { - x: 586347.706288 - y: 4140711.21271 - theta: 1.30459245364 - kappa: 2.83232967619e-05 - dkappa: 5.77878677039e-06 - } - path_point { - x: 586347.748463 - y: 4140711.36738 - theta: 1.30459706669 - kappa: 2.92119622088e-05 - dkappa: 5.30371128972e-06 - } - path_point { - x: 586347.790638 - y: 4140711.52206 - theta: 1.30460181601 - kappa: 3.00227165351e-05 - dkappa: 4.80685053796e-06 - } - path_point { - x: 586347.832811 - y: 4140711.67673 - theta: 1.30460668883 - kappa: 3.07520673382e-05 - dkappa: 4.28820517534e-06 - } - path_point { - x: 586347.874984 - y: 4140711.8314 - theta: 1.30461167182 - kappa: 3.1396522313e-05 - dkappa: 3.7477758871e-06 - } - path_point { - x: 586347.917156 - y: 4140711.98608 - theta: 1.30461675108 - kappa: 3.19525892557e-05 - dkappa: 3.18556337826e-06 - } - path_point { - x: 586347.959328 - y: 4140712.14075 - theta: 1.30462191217 - kappa: 3.2416776065e-05 - dkappa: 2.601568368e-06 - } - path_point { - x: 586348.001498 - y: 4140712.29543 - theta: 1.30462714008 - kappa: 3.27855907437e-05 - dkappa: 1.99579158383e-06 - } - path_point { - x: 586348.043668 - y: 4140712.4501 - theta: 1.30463241924 - kappa: 3.30555413989e-05 - dkappa: 1.3682337555e-06 - } - path_point { - x: 586348.085837 - y: 4140712.60477 - theta: 1.30463773351 - kappa: 3.32231362417e-05 - dkappa: 7.18895608591e-07 - } - path_point { - x: 586348.128005 - y: 4140712.75945 - theta: 1.30464306622 - kappa: 3.32848835853e-05 - dkappa: 4.77778579045e-08 - } - path_point { - x: 586348.170172 - y: 4140712.91412 - theta: 1.3046484001 - kappa: 3.32372918432e-05 - dkappa: -6.4511879948e-07 - } - path_point { - x: 586348.212338 - y: 4140713.0688 - theta: 1.30465371736 - kappa: 3.30768695251e-05 - dkappa: -1.35979369138e-06 - } - path_point { - x: 586348.254504 - y: 4140713.22347 - theta: 1.30465899962 - kappa: 3.28001252331e-05 - dkappa: -2.09624617795e-06 - } - path_point { - x: 586348.296668 - y: 4140713.37815 - theta: 1.30466422796 - kappa: 3.24035676559e-05 - dkappa: -2.85447565943e-06 - } - path_point { - x: 586348.338832 - y: 4140713.53282 - theta: 1.30466938288 - kappa: 3.18837055621e-05 - dkappa: -3.63448158412e-06 - } - path_point { - x: 586348.380995 - y: 4140713.6875 - theta: 1.30467444434 - kappa: 3.12370477927e-05 - dkappa: -4.43626345662e-06 - } - path_point { - x: 586348.423158 - y: 4140713.84218 - theta: 1.30467939173 - kappa: 3.0460103252e-05 - dkappa: -5.25982084639e-06 - } - path_point { - x: 586348.465319 - y: 4140713.99685 - theta: 1.30468420388 - kappa: 2.95493808976e-05 - dkappa: -6.10515339652e-06 - } - path_point { - x: 586348.50748 - y: 4140714.15153 - theta: 1.30468885907 - kappa: 2.85013897287e-05 - dkappa: -6.97226083278e-06 - } - path_point { - x: 586348.54964 - y: 4140714.30621 - theta: 1.30469333501 - kappa: 2.73126387737e-05 - dkappa: -7.86114297298e-06 - } - path_point { - x: 586348.5918 - y: 4140714.46088 - theta: 1.3046976115 - kappa: 2.60389750089e-05 - dkappa: -7.88103240124e-06 - } - path_point { - x: 586348.633958 - y: 4140714.61556 - theta: 1.30470168544 - kappa: 2.47880076154e-05 - dkappa: -7.72496301075e-06 - } - path_point { - x: 586348.676117 - y: 4140714.77024 - theta: 1.30470556084 - kappa: 2.3562027752e-05 - dkappa: -7.56930848048e-06 - } - path_point { - x: 586348.718274 - y: 4140714.92491 - theta: 1.30470924168 - kappa: 2.23609688823e-05 - dkappa: -7.41406902029e-06 - } - path_point { - x: 586348.760431 - y: 4140715.07959 - theta: 1.30471273197 - kappa: 2.11847644398e-05 - dkappa: -7.25924482851e-06 - } - path_point { - x: 586348.802588 - y: 4140715.23427 - theta: 1.30471603568 - kappa: 2.00333478291e-05 - dkappa: -7.10483609228e-06 - } - path_point { - x: 586348.844744 - y: 4140715.38895 - theta: 1.30471915677 - kappa: 1.8906652428e-05 - dkappa: -6.95084298784e-06 - } - path_point { - x: 586348.8869 - y: 4140715.54363 - theta: 1.30472209921 - kappa: 1.78046115888e-05 - dkappa: -6.79726568077e-06 - } - path_point { - x: 586348.929055 - y: 4140715.6983 - theta: 1.30472486695 - kappa: 1.67271586401e-05 - dkappa: -6.64410432638e-06 - } - path_point { - x: 586348.97121 - y: 4140715.85298 - theta: 1.30472746391 - kappa: 1.56742268878e-05 - dkappa: -6.4913590699e-06 - } - path_point { - x: 586349.013364 - y: 4140716.00766 - theta: 1.30472989403 - kappa: 1.4645749617e-05 - dkappa: -6.33903004684e-06 - } - path_point { - x: 586349.055518 - y: 4140716.16234 - theta: 1.30473216122 - kappa: 1.36416600934e-05 - dkappa: -6.18711738323e-06 - } - path_point { - x: 586349.097672 - y: 4140716.31702 - theta: 1.30473426939 - kappa: 1.26618915642e-05 - dkappa: -6.03562119594e-06 - } - path_point { - x: 586349.139825 - y: 4140716.4717 - theta: 1.30473622242 - kappa: 1.17063772599e-05 - dkappa: -5.88454159295e-06 - } - path_point { - x: 586349.181978 - y: 4140716.62638 - theta: 1.30473802421 - kappa: 1.07750503955e-05 - dkappa: -5.73387867363e-06 - } - path_point { - x: 586349.224131 - y: 4140716.78106 - theta: 1.30473967863 - kappa: 9.86784417146e-06 - dkappa: -5.58363252903e-06 - } - path_point { - x: 586349.266284 - y: 4140716.93573 - theta: 1.30474118952 - kappa: 8.9846917753e-06 - dkappa: -5.43380324213e-06 - } - path_point { - x: 586349.308436 - y: 4140717.09041 - theta: 1.30474256076 - kappa: 8.12552638244e-06 - dkappa: -5.28439088817e-06 - } - path_point { - x: 586349.350589 - y: 4140717.24509 - theta: 1.30474379617 - kappa: 7.29028115746e-06 - dkappa: -5.13539553487e-06 - } - path_point { - x: 586349.392741 - y: 4140717.39977 - theta: 1.30474489959 - kappa: 6.47888925515e-06 - dkappa: -4.98681724275e-06 - } - path_point { - x: 586349.434893 - y: 4140717.55445 - theta: 1.30474587484 - kappa: 5.69128382157e-06 - dkappa: -4.83865606537e-06 - } - path_point { - x: 586349.477044 - y: 4140717.70913 - theta: 1.30474672572 - kappa: 4.92739799505e-06 - dkappa: -4.69091204963e-06 - } - path_point { - x: 586349.519196 - y: 4140717.86381 - theta: 1.30474745603 - kappa: 4.18716490711e-06 - dkappa: -4.54358523599e-06 - } - path_point { - x: 586349.561348 - y: 4140718.01849 - theta: 1.30474806955 - kappa: 3.47051768342e-06 - dkappa: -4.39667565882e-06 - } - path_point { - x: 586349.603499 - y: 4140718.17317 - theta: 1.30474857007 - kappa: 2.7773894447e-06 - dkappa: -4.25018334657e-06 - } - path_point { - x: 586349.645651 - y: 4140718.32785 - theta: 1.30474896135 - kappa: 2.10771330751e-06 - dkappa: -4.10410832212e-06 - } - path_point { - x: 586349.687802 - y: 4140718.48253 - theta: 1.30474924714 - kappa: 1.4614223851e-06 - dkappa: -3.95845060297e-06 - } - path_point { - x: 586349.729953 - y: 4140718.63721 - theta: 1.30474943119 - kappa: 8.38449788167e-07 - dkappa: -3.81321020157e-06 - } - path_point { - x: 586349.772105 - y: 4140718.79189 - theta: 1.30474951722 - kappa: 2.38728625581e-07 - dkappa: -3.66838712552e-06 - } - path_point { - x: 586349.814256 - y: 4140718.94657 - theta: 1.30474950897 - kappa: -3.37807994916e-07 - dkappa: -3.52398137788e-06 - } - path_point { - x: 586349.856408 - y: 4140719.10125 - theta: 1.30474941014 - kappa: -8.91226966054e-07 - dkappa: -3.37999295737e-06 - } - path_point { - x: 586349.898559 - y: 4140719.25593 - theta: 1.30474922444 - kappa: -1.42159518042e-06 - dkappa: -3.23642185869e-06 - } - path_point { - x: 586349.940711 - y: 4140719.41061 - theta: 1.30474895555 - kappa: -1.92897952987e-06 - dkappa: -3.09326807272e-06 - } - path_point { - x: 586349.982862 - y: 4140719.56529 - theta: 1.30474860715 - kappa: -2.413446905e-06 - dkappa: -2.95053158678e-06 - } - path_point { - x: 586350.025014 - y: 4140719.71997 - theta: 1.30474818292 - kappa: -2.87506419462e-06 - dkappa: -2.80821238493e-06 - } - path_point { - x: 586350.067165 - y: 4140719.87465 - theta: 1.30474768651 - kappa: -3.31389828527e-06 - dkappa: -2.66631044815e-06 - } - path_point { - x: 586350.109317 - y: 4140720.02933 - theta: 1.30474712156 - kappa: -3.73001606083e-06 - dkappa: -2.52482575463e-06 - } - path_point { - x: 586350.151469 - y: 4140720.18401 - theta: 1.30474649172 - kappa: -4.12348440207e-06 - dkappa: -2.38375827999e-06 - } - path_point { - x: 586350.193621 - y: 4140720.33869 - theta: 1.30474580061 - kappa: -4.49437018631e-06 - dkappa: -2.24310799756e-06 - } - path_point { - x: 586350.235773 - y: 4140720.49337 - theta: 1.30474505184 - kappa: -4.84274028711e-06 - dkappa: -2.10287487859e-06 - } - path_point { - x: 586350.277925 - y: 4140720.64805 - theta: 1.30474424902 - kappa: -5.16866157392e-06 - dkappa: -1.9630588925e-06 - } - path_point { - x: 586350.320077 - y: 4140720.80273 - theta: 1.30474339575 - kappa: -5.47220091187e-06 - dkappa: -1.82366000711e-06 - } - path_point { - x: 586350.36223 - y: 4140720.95741 - theta: 1.3047424956 - kappa: -5.75342516152e-06 - dkappa: -1.68467818891e-06 - } - path_point { - x: 586350.404383 - y: 4140721.11209 - theta: 1.30474155215 - kappa: -6.01240117871e-06 - dkappa: -1.54611340326e-06 - } - path_point { - x: 586350.446535 - y: 4140721.26677 - theta: 1.30474056896 - kappa: -6.24919581432e-06 - dkappa: -1.40796561465e-06 - } - path_point { - x: 586350.488688 - y: 4140721.42145 - theta: 1.30473954958 - kappa: -6.46387591426e-06 - dkappa: -1.2702347869e-06 - } - path_point { - x: 586350.530841 - y: 4140721.57613 - theta: 1.30473849755 - kappa: -6.65650831929e-06 - dkappa: -1.13292088344e-06 - } - path_point { - x: 586350.572995 - y: 4140721.73081 - theta: 1.3047374164 - kappa: -6.82715986501e-06 - dkappa: -9.960238675e-07 - } - path_point { - x: 586350.615148 - y: 4140721.88549 - theta: 1.30473630965 - kappa: -6.97589738183e-06 - dkappa: -8.59543702354e-07 - } - path_point { - x: 586350.657302 - y: 4140722.04017 - theta: 1.3047351808 - kappa: -7.10278769498e-06 - dkappa: -7.23480351548e-07 - } - path_point { - x: 586350.699455 - y: 4140722.19485 - theta: 1.30473403336 - kappa: -7.20789762457e-06 - dkappa: -5.87833779119e-07 - } - path_point { - x: 586350.741609 - y: 4140722.34953 - theta: 1.30473287081 - kappa: -7.29129398565e-06 - dkappa: -4.52603949823e-07 - } - path_point { - x: 586350.783763 - y: 4140722.50421 - theta: 1.30473169663 - kappa: -7.35304358833e-06 - dkappa: -3.17790829359e-07 - } - path_point { - x: 586350.825918 - y: 4140722.65889 - theta: 1.30473051427 - kappa: -7.39321323793e-06 - dkappa: -1.83394384584e-07 - } - path_point { - x: 586350.868072 - y: 4140722.81357 - theta: 1.30472932721 - kappa: -7.41186973512e-06 - dkappa: -4.94145837388e-08 - } - path_point { - x: 586350.910227 - y: 4140722.96825 - theta: 1.30472813887 - kappa: -7.40907987619e-06 - dkappa: 8.41486033409e-08 - } - path_point { - x: 586350.952382 - y: 4140723.12293 - theta: 1.30472695269 - kappa: -7.38491045324e-06 - dkappa: 2.17295205003e-07 - } - path_point { - x: 586350.994537 - y: 4140723.27761 - theta: 1.3047257721 - kappa: -7.33942825446e-06 - dkappa: 3.50025247567e-07 - } - path_point { - x: 586351.036692 - y: 4140723.43229 - theta: 1.3047246005 - kappa: -7.27270006445e-06 - dkappa: 4.82338755112e-07 - } - path_point { - x: 586351.078847 - y: 4140723.58697 - theta: 1.3047234413 - kappa: -7.18479266452e-06 - dkappa: 6.1423574926e-07 - } - path_point { - x: 586351.121003 - y: 4140723.74165 - theta: 1.30472229788 - kappa: -7.0757728331e-06 - dkappa: 7.45716248974e-07 - } - path_point { - x: 586351.163159 - y: 4140723.89633 - theta: 1.30472117364 - kappa: -6.94570734609e-06 - dkappa: 8.76780270342e-07 - } - path_point { - x: 586351.205315 - y: 4140724.05101 - theta: 1.30472007192 - kappa: -6.79466297732e-06 - dkappa: 1.00742782637e-06 - } - path_point { - x: 586351.247471 - y: 4140724.20569 - theta: 1.3047189961 - kappa: -6.62270649896e-06 - dkappa: 1.1376589268e-06 - } - path_point { - x: 586351.289627 - y: 4140724.36036 - theta: 1.30471794952 - kappa: -6.42990468206e-06 - dkappa: 1.26747357785e-06 - } - path_point { - x: 586351.331783 - y: 4140724.51504 - theta: 1.30471693552 - kappa: -6.21632429704e-06 - dkappa: 1.39687178207e-06 - } - path_point { - x: 586351.37394 - y: 4140724.66972 - theta: 1.30471595742 - kappa: -5.98203211422e-06 - dkappa: 1.52585353812e-06 - } - path_point { - x: 586351.416096 - y: 4140724.8244 - theta: 1.30471501854 - kappa: -5.72709490441e-06 - dkappa: 1.65441884057e-06 - } - path_point { - x: 586351.458253 - y: 4140724.97908 - theta: 1.30471412218 - kappa: -5.45157943952e-06 - dkappa: 1.78256767968e-06 - } - path_point { - x: 586351.50041 - y: 4140725.13376 - theta: 1.30471327163 - kappa: -5.15555249316e-06 - dkappa: 1.91030004126e-06 - } - path_point { - x: 586351.542567 - y: 4140725.28844 - theta: 1.30471247019 - kappa: -4.83908084135e-06 - dkappa: 2.03761590641e-06 - } - path_point { - x: 586351.584724 - y: 4140725.44312 - theta: 1.30471172111 - kappa: -4.50223126317e-06 - dkappa: 2.16451525137e-06 - } - path_point { - x: 586351.626882 - y: 4140725.59779 - theta: 1.30471102767 - kappa: -4.14507054149e-06 - dkappa: 2.29099804731e-06 - } - path_point { - x: 586351.669039 - y: 4140725.75247 - theta: 1.30471039311 - kappa: -3.7676654637e-06 - dkappa: 2.41706426015e-06 - } - path_point { - x: 586351.711196 - y: 4140725.90715 - theta: 1.30470982068 - kappa: -3.37008282254e-06 - dkappa: 2.54271385037e-06 - } - path_point { - x: 586351.753354 - y: 4140726.06183 - theta: 1.3047093136 - kappa: -2.95238941681e-06 - dkappa: 2.66794677281e-06 - } - path_point { - x: 586351.795512 - y: 4140726.21651 - theta: 1.3047088751 - kappa: -2.51465205227e-06 - dkappa: 2.79276297649e-06 - } - path_point { - x: 586351.837669 - y: 4140726.37119 - theta: 1.30470850837 - kappa: -2.05693754249e-06 - dkappa: 2.91716240445e-06 - } - path_point { - x: 586351.879827 - y: 4140726.52586 - theta: 1.30470821662 - kappa: -1.57931270968e-06 - dkappa: 3.04114499352e-06 - } - path_point { - x: 586351.921985 - y: 4140726.68054 - theta: 1.30470800304 - kappa: -1.08184438568e-06 - dkappa: 3.16471067418e-06 - } - path_point { - x: 586351.964143 - y: 4140726.83522 - theta: 1.30470787079 - kappa: -5.645994128e-07 - dkappa: 3.28785937036e-06 - } - path_point { - x: 586352.0063 - y: 4140726.9899 - theta: 1.30470782306 - kappa: -2.76446448788e-08 - dkappa: 3.41059099928e-06 - } - path_point { - x: 586352.048458 - y: 4140727.14458 - theta: 1.30470786298 - kappa: 5.28953051794e-07 - dkappa: 3.53290547125e-06 - } - path_point { - x: 586352.090616 - y: 4140727.29926 - theta: 1.30470799322 - kappa: 1.09134923158e-06 - dkappa: 3.39749888408e-06 - } - path_point { - x: 586352.132774 - y: 4140727.45393 - theta: 1.30470821073 - kappa: 1.61521019868e-06 - dkappa: 3.13875233739e-06 - } - path_point { - x: 586352.174931 - y: 4140727.60861 - theta: 1.30470850893 - kappa: 2.09810648077e-06 - dkappa: 2.88646368475e-06 - } - path_point { - x: 586352.217089 - y: 4140727.76329 - theta: 1.30470888133 - kappa: 2.54107342365e-06 - dkappa: 2.64063302957e-06 - } - path_point { - x: 586352.259247 - y: 4140727.91797 - theta: 1.30470932162 - kappa: 2.94514638685e-06 - dkappa: 2.40126046296e-06 - } - path_point { - x: 586352.301404 - y: 4140728.07265 - theta: 1.30470982364 - kappa: 3.31136074193e-06 - dkappa: 2.16834606452e-06 - } - path_point { - x: 586352.343562 - y: 4140728.22733 - theta: 1.30471038141 - kappa: 3.64075187094e-06 - dkappa: 1.94188990303e-06 - } - path_point { - x: 586352.385719 - y: 4140728.382 - theta: 1.30471098911 - kappa: 3.93435516495e-06 - dkappa: 1.72189203717e-06 - } - path_point { - x: 586352.427876 - y: 4140728.53668 - theta: 1.30471164107 - kappa: 4.19320602266e-06 - dkappa: 1.50835251621e-06 - } - path_point { - x: 586352.470033 - y: 4140728.69136 - theta: 1.30471233182 - kappa: 4.41833984911e-06 - dkappa: 1.30127138066e-06 - } - path_point { - x: 586352.51219 - y: 4140728.84604 - theta: 1.30471305602 - kappa: 4.61079205456e-06 - dkappa: 1.10064866292e-06 - } - path_point { - x: 586352.554347 - y: 4140729.00072 - theta: 1.30471380853 - kappa: 4.77159805333e-06 - dkappa: 9.06484387944e-07 - } - path_point { - x: 586352.596504 - y: 4140729.1554 - theta: 1.30471458436 - kappa: 4.90179326281e-06 - dkappa: 7.18778573779e-07 - } - path_point { - x: 586352.638661 - y: 4140729.31007 - theta: 1.30471537867 - kappa: 5.00241310257e-06 - dkappa: 5.37531232215e-07 - } - path_point { - x: 586352.680818 - y: 4140729.46475 - theta: 1.30471618681 - kappa: 5.07449299348e-06 - dkappa: 3.62742369327e-07 - } - path_point { - x: 586352.722974 - y: 4140729.61943 - theta: 1.30471700429 - kappa: 5.11906835694e-06 - dkappa: 1.94411986028e-07 - } - path_point { - x: 586352.76513 - y: 4140729.77411 - theta: 1.30471782678 - kappa: 5.13717461423e-06 - dkappa: 3.2540078605e-08 - } - path_point { - x: 586352.807287 - y: 4140729.92879 - theta: 1.30471865012 - kappa: 5.12984718587e-06 - dkappa: -1.22873360775e-07 - } - path_point { - x: 586352.849443 - y: 4140730.08347 - theta: 1.30471947032 - kappa: 5.09812149107e-06 - dkappa: -2.71828343569e-07 - } - path_point { - x: 586352.891599 - y: 4140730.23815 - theta: 1.30472028354 - kappa: 5.04303294726e-06 - dkappa: -4.14324884388e-07 - } - path_point { - x: 586352.933755 - y: 4140730.39283 - theta: 1.30472108613 - kappa: 4.96561696969e-06 - dkappa: -5.5036300054e-07 - } - path_point { - x: 586352.97591 - y: 4140730.54751 - theta: 1.30472187459 - kappa: 4.86690897107e-06 - dkappa: -6.79942711599e-07 - } - path_point { - x: 586353.018066 - y: 4140730.70218 - theta: 1.30472264558 - kappa: 4.74794436127e-06 - dkappa: -8.03064038989e-07 - } - path_point { - x: 586353.060222 - y: 4140730.85686 - theta: 1.30472339595 - kappa: 4.60975854708e-06 - dkappa: -9.19727005587e-07 - } - path_point { - x: 586353.102377 - y: 4140731.01154 - theta: 1.30472412269 - kappa: 4.45338693209e-06 - dkappa: -1.02993163535e-06 - } - path_point { - x: 586353.144532 - y: 4140731.16622 - theta: 1.30472482297 - kappa: 4.27986491646e-06 - dkappa: -1.13367795295e-06 - } - path_point { - x: 586353.186687 - y: 4140731.3209 - theta: 1.30472549413 - kappa: 4.09022789694e-06 - dkappa: -1.23096598345e-06 - } - path_point { - x: 586353.228843 - y: 4140731.47558 - theta: 1.30472613366 - kappa: 3.88551126678e-06 - dkappa: -1.32179575198e-06 - } - path_point { - x: 586353.270998 - y: 4140731.63026 - theta: 1.30472673923 - kappa: 3.66675041575e-06 - dkappa: -1.40616728341e-06 - } - path_point { - x: 586353.313152 - y: 4140731.78494 - theta: 1.30472730868 - kappa: 3.4349807302e-06 - dkappa: -1.48408060214e-06 - } - path_point { - x: 586353.355307 - y: 4140731.93962 - theta: 1.30472783999 - kappa: 3.19123759314e-06 - dkappa: -1.55553573176e-06 - } - path_point { - x: 586353.397462 - y: 4140732.0943 - theta: 1.30472833134 - kappa: 2.93655638436e-06 - dkappa: -1.62053269485e-06 - } - path_point { - x: 586353.439617 - y: 4140732.24898 - theta: 1.30472878104 - kappa: 2.6719724806e-06 - dkappa: -1.67907151277e-06 - } - path_point { - x: 586353.481771 - y: 4140732.40366 - theta: 1.30472918761 - kappa: 2.39852125572e-06 - dkappa: -1.73115220542e-06 - } - path_point { - x: 586353.523926 - y: 4140732.55834 - theta: 1.30472954969 - kappa: 2.11723808092e-06 - dkappa: -1.77677479109e-06 - } - path_point { - x: 586353.56608 - y: 4140732.71302 - theta: 1.30472986612 - kappa: 1.82915832498e-06 - dkappa: -1.81593928628e-06 - } - path_point { - x: 586353.608235 - y: 4140732.8677 - theta: 1.30473013589 - kappa: 1.53531735451e-06 - dkappa: -1.84864570556e-06 - } - path_point { - x: 586353.650389 - y: 4140733.02238 - theta: 1.30473035815 - kappa: 1.23675053423e-06 - dkappa: -1.87489406145e-06 - } - path_point { - x: 586353.692544 - y: 4140733.17706 - theta: 1.30473053224 - kappa: 9.34493227262e-07 - dkappa: -1.89468436428e-06 - } - path_point { - x: 586353.734698 - y: 4140733.33174 - theta: 1.30473065765 - kappa: 6.29580795453e-07 - dkappa: -1.90801662217e-06 - } - path_point { - x: 586353.776853 - y: 4140733.48641 - theta: 1.30473073403 - kappa: 3.23048599664e-07 - dkappa: -1.9148908409e-06 - } - path_point { - x: 586353.819007 - y: 4140733.64109 - theta: 1.3047307612 - kappa: 1.59320001169e-08 - dkappa: -1.9153070239e-06 - } - path_point { - x: 586353.861161 - y: 4140733.79577 - theta: 1.30473073916 - kappa: -2.90733643283e-07 - dkappa: -1.90926517221e-06 - } - path_point { - x: 586353.903316 - y: 4140733.95045 - theta: 1.30473066806 - kappa: -5.95912970611e-07 - dkappa: -1.89676528445e-06 - } - path_point { - x: 586353.94547 - y: 4140734.10513 - theta: 1.30473054822 - kappa: -8.98570621593e-07 - dkappa: -1.87780735687e-06 - } - path_point { - x: 586353.987624 - y: 4140734.25981 - theta: 1.30473038013 - kappa: -1.19767123527e-06 - dkappa: -1.85239138335e-06 - } - path_point { - x: 586354.029779 - y: 4140734.41449 - theta: 1.30473016444 - kappa: -1.49217944968e-06 - dkappa: -1.82051735547e-06 - } - path_point { - x: 586354.071933 - y: 4140734.56917 - theta: 1.30472990198 - kappa: -1.78105990152e-06 - dkappa: -1.78218526255e-06 - } - path_point { - x: 586354.114088 - y: 4140734.72385 - theta: 1.30472959372 - kappa: -2.0632772259e-06 - dkappa: -1.73739509177e-06 - } - path_point { - x: 586354.156242 - y: 4140734.87853 - theta: 1.30472924082 - kappa: -2.33779605595e-06 - dkappa: -1.68614682825e-06 - } - path_point { - x: 586354.198397 - y: 4140735.03321 - theta: 1.30472884459 - kappa: -2.60358102266e-06 - dkappa: -1.6284404552e-06 - } - path_point { - x: 586354.240552 - y: 4140735.18789 - theta: 1.30472840652 - kappa: -2.85959675452e-06 - dkappa: -1.56427595404e-06 - } - path_point { - x: 586354.282707 - y: 4140735.34257 - theta: 1.30472792826 - kappa: -3.10480787737e-06 - dkappa: -1.4936533046e-06 - } - path_point { - x: 586354.324861 - y: 4140735.49725 - theta: 1.30472741162 - kappa: -3.33817901413e-06 - dkappa: -1.41657248526e-06 - } - path_point { - x: 586354.367016 - y: 4140735.65193 - theta: 1.30472685859 - kappa: -3.55867478464e-06 - dkappa: -1.33303347318e-06 - } - path_point { - x: 586354.409171 - y: 4140735.80661 - theta: 1.30472627131 - kappa: -3.76525980551e-06 - dkappa: -1.24303624454e-06 - } - path_point { - x: 586354.451326 - y: 4140735.96129 - theta: 1.30472565209 - kappa: -3.95689869001e-06 - dkappa: -1.14658077474e-06 - } - path_point { - x: 586354.493482 - y: 4140736.11597 - theta: 1.30472500342 - kappa: -4.13255604796e-06 - dkappa: -1.0436670387e-06 - } - path_point { - x: 586354.535637 - y: 4140736.27065 - theta: 1.30472432793 - kappa: -4.29119648568e-06 - dkappa: -9.3429501111e-07 - } - path_point { - x: 586354.577792 - y: 4140736.42533 - theta: 1.30472362844 - kappa: -4.43178460603e-06 - dkappa: -8.1846466676e-07 - } - path_point { - x: 586354.619948 - y: 4140736.58 - theta: 1.30472290794 - kappa: -4.55328500839e-06 - dkappa: -6.96175980835e-07 - } - path_point { - x: 586354.662103 - y: 4140736.73468 - theta: 1.30472216955 - kappa: -4.65466228879e-06 - dkappa: -5.67428929268e-07 - } - path_point { - x: 586354.704259 - y: 4140736.88936 - theta: 1.30472141659 - kappa: -4.73488104002e-06 - dkappa: -4.32223489093e-07 - } - path_point { - x: 586354.746415 - y: 4140737.04404 - theta: 1.30472065254 - kappa: -4.7929058518e-06 - dkappa: -2.90559638825e-07 - } - path_point { - x: 586354.788571 - y: 4140737.19872 - theta: 1.30471988103 - kappa: -4.82770131106e-06 - dkappa: -1.42437358854e-07 - } - path_point { - x: 586354.830727 - y: 4140737.3534 - theta: 1.30471910587 - kappa: -4.83823200221e-06 - dkappa: 1.21433681353e-08 - } - path_point { - x: 586354.872883 - y: 4140737.50808 - theta: 1.30471833104 - kappa: -4.82346250748e-06 - dkappa: 1.73182556731e-07 - } - path_point { - x: 586354.915039 - y: 4140737.66276 - theta: 1.30471756068 - kappa: -4.78235740739e-06 - dkappa: 3.40680218338e-07 - } - path_point { - x: 586354.957195 - y: 4140737.81744 - theta: 1.30471679909 - kappa: -4.71388128116e-06 - dkappa: 5.14636360703e-07 - } - path_point { - x: 586354.999352 - y: 4140737.97211 - theta: 1.30471605073 - kappa: -4.61699870734e-06 - dkappa: 6.95050987421e-07 - } - path_point { - x: 586355.041509 - y: 4140738.12679 - theta: 1.30471532026 - kappa: -4.49067426437e-06 - dkappa: 8.81924097424e-07 - } - path_point { - x: 586355.083665 - y: 4140738.28147 - theta: 1.30471461247 - kappa: -4.3338725313e-06 - dkappa: 1.07525568445e-06 - } - path_point { - x: 586355.125822 - y: 4140738.43615 - theta: 1.30471393233 - kappa: -4.14555808857e-06 - dkappa: 1.27504573649e-06 - } - path_point { - x: 586355.167979 - y: 4140738.59083 - theta: 1.30471328497 - kappa: -3.92469551884e-06 - dkappa: 1.4812942352e-06 - } - path_point { - x: 586355.210136 - y: 4140738.74551 - theta: 1.3047126757 - kappa: -3.67024940795e-06 - dkappa: 1.69400115536e-06 - } - path_point { - x: 586355.252293 - y: 4140738.90019 - theta: 1.30471210999 - kappa: -3.38118434589e-06 - dkappa: 1.91316646421e-06 - } - path_point { - x: 586355.29445 - y: 4140739.05486 - theta: 1.30471159346 - kappa: -3.05646492796e-06 - dkappa: 2.13879012085e-06 - } - path_point { - x: 586355.336608 - y: 4140739.20954 - theta: 1.30471113192 - kappa: -2.6950557559e-06 - dkappa: 2.37087207558e-06 - } - path_point { - x: 586355.378765 - y: 4140739.36422 - theta: 1.30471073133 - kappa: -2.29592143923e-06 - dkappa: 2.60941226923e-06 - } - path_point { - x: 586355.420922 - y: 4140739.5189 - theta: 1.30471039783 - kappa: -1.85802659661e-06 - dkappa: 2.85441063251e-06 - } - path_point { - x: 586355.46308 - y: 4140739.67358 - theta: 1.3047101377 - kappa: -1.38033585729e-06 - dkappa: 3.10586708525e-06 - } - path_point { - x: 586355.505237 - y: 4140739.82826 - theta: 1.30470995742 - kappa: -8.61813862723e-07 - dkappa: 3.36378153571e-06 - } - path_point { - x: 586355.547395 - y: 4140739.98293 - theta: 1.30470986361 - kappa: -3.01425268243e-07 - dkappa: 3.6281538798e-06 - } - path_point { - x: 586355.589552 - y: 4140740.13761 - theta: 1.30470986277 - kappa: 2.91000255331e-07 - dkappa: 3.62790450026e-06 - } - path_point { - x: 586355.631709 - y: 4140740.29229 - theta: 1.30470995491 - kappa: 8.51311903692e-07 - dkappa: 3.36308175428e-06 - } - path_point { - x: 586355.673867 - y: 4140740.44697 - theta: 1.3047101335 - kappa: 1.36968991213e-06 - dkappa: 3.10478137809e-06 - } - path_point { - x: 586355.716024 - y: 4140740.60165 - theta: 1.3047103919 - kappa: 1.84717996213e-06 - dkappa: 2.85300347567e-06 - } - path_point { - x: 586355.758182 - y: 4140740.75633 - theta: 1.30471072365 - kappa: 2.28482774903e-06 - dkappa: 2.60774813867e-06 - } - path_point { - x: 586355.800339 - y: 4140740.911 - theta: 1.30471112244 - kappa: 2.68367898033e-06 - dkappa: 2.36901544721e-06 - } - path_point { - x: 586355.842496 - y: 4140741.06568 - theta: 1.30471158213 - kappa: 3.04477937415e-06 - dkappa: 2.13680547052e-06 - } - path_point { - x: 586355.884653 - y: 4140741.22036 - theta: 1.30471209676 - kappa: 3.36917465775e-06 - dkappa: 1.91111826775e-06 - } - path_point { - x: 586355.926811 - y: 4140741.37504 - theta: 1.30471266052 - kappa: 3.65791056614e-06 - dkappa: 1.69195388856e-06 - } - path_point { - x: 586355.968968 - y: 4140741.52972 - theta: 1.30471326778 - kappa: 3.91203284079e-06 - dkappa: 1.47931237385e-06 - } - path_point { - x: 586356.011124 - y: 4140741.6844 - theta: 1.30471391308 - kappa: 4.13258722846e-06 - dkappa: 1.27319375637e-06 - } - path_point { - x: 586356.053281 - y: 4140741.83907 - theta: 1.30471459112 - kappa: 4.32061948008e-06 - dkappa: 1.07359806136e-06 - } - path_point { - x: 586356.095438 - y: 4140741.99375 - theta: 1.30471529677 - kappa: 4.47717534977e-06 - dkappa: 8.80525307172e-07 - } - path_point { - x: 586356.137595 - y: 4140742.14843 - theta: 1.30471602506 - kappa: 4.60330059385e-06 - dkappa: 6.93975505828e-07 - } - path_point { - x: 586356.179751 - y: 4140742.30311 - theta: 1.3047167712 - kappa: 4.70004097006e-06 - dkappa: 5.13948663615e-07 - } - path_point { - x: 586356.221908 - y: 4140742.45779 - theta: 1.30471753057 - kappa: 4.76844223675e-06 - dkappa: 3.40444781625e-07 - } - path_point { - x: 586356.264064 - y: 4140742.61247 - theta: 1.3047182987 - kappa: 4.80955015216e-06 - dkappa: 1.73463856286e-07 - } - path_point { - x: 586356.30622 - y: 4140742.76715 - theta: 1.30471907131 - kappa: 4.82441047386e-06 - dkappa: 1.30058798784e-08 - } - path_point { - x: 586356.348376 - y: 4140742.92183 - theta: 1.30471984426 - kappa: 4.81406895817e-06 - dkappa: -1.40929158979e-07 - } - path_point { - x: 586356.390532 - y: 4140743.07651 - theta: 1.30472061361 - kappa: 4.77957135965e-06 - dkappa: -2.8834127485e-07 - } - path_point { - x: 586356.432688 - y: 4140743.23118 - theta: 1.30472137555 - kappa: 4.72196343073e-06 - dkappa: -4.29230485032e-07 - } - path_point { - x: 586356.474843 - y: 4140743.38586 - theta: 1.30472212648 - kappa: 4.64229092132e-06 - dkappa: -5.63596809116e-07 - } - path_point { - x: 586356.516999 - y: 4140743.54054 - theta: 1.30472286294 - kappa: 4.54159957852e-06 - dkappa: -6.91440268573e-07 - } - path_point { - x: 586356.559155 - y: 4140743.69522 - theta: 1.30472358164 - kappa: 4.42093514639e-06 - dkappa: -8.12760886362e-07 - } - path_point { - x: 586356.60131 - y: 4140743.8499 - theta: 1.30472427946 - kappa: 4.28134336575e-06 - dkappa: -9.27558686544e-07 - } - path_point { - x: 586356.643465 - y: 4140744.00458 - theta: 1.30472495346 - kappa: 4.12386997406e-06 - dkappa: -1.03583369393e-06 - } - path_point { - x: 586356.68562 - y: 4140744.15926 - theta: 1.30472560085 - kappa: 3.94956070535e-06 - dkappa: -1.13758593375e-06 - } - path_point { - x: 586356.727775 - y: 4140744.31394 - theta: 1.30472621901 - kappa: 3.75946129012e-06 - dkappa: -1.23281543131e-06 - } - path_point { - x: 586356.76993 - y: 4140744.46862 - theta: 1.3047268055 - kappa: 3.55461745543e-06 - dkappa: -1.32152221172e-06 - } - path_point { - x: 586356.812085 - y: 4140744.6233 - theta: 1.30472735804 - kappa: 3.33607492487e-06 - dkappa: -1.4037062996e-06 - } - path_point { - x: 586356.85424 - y: 4140744.77798 - theta: 1.30472787451 - kappa: 3.10487941869e-06 - dkappa: -1.47936771879e-06 - } - path_point { - x: 586356.896395 - y: 4140744.93266 - theta: 1.30472835297 - kappa: 2.86207665389e-06 - dkappa: -1.54850649218e-06 - } - path_point { - x: 586356.93855 - y: 4140745.08734 - theta: 1.30472879164 - kappa: 2.60871234442e-06 - dkappa: -1.61112264141e-06 - } - path_point { - x: 586356.980704 - y: 4140745.24202 - theta: 1.30472918892 - kappa: 2.3458322013e-06 - dkappa: -1.66721618671e-06 - } - path_point { - x: 586357.022859 - y: 4140745.39669 - theta: 1.30472954336 - kappa: 2.07448193285e-06 - dkappa: -1.71678714671e-06 - } - path_point { - x: 586357.065013 - y: 4140745.55137 - theta: 1.30472985369 - kappa: 1.79570724495e-06 - dkappa: -1.75983553824e-06 - } - path_point { - x: 586357.107168 - y: 4140745.70605 - theta: 1.3047301188 - kappa: 1.51055384128e-06 - dkappa: -1.79636137625e-06 - } - path_point { - x: 586357.149322 - y: 4140745.86073 - theta: 1.30473033775 - kappa: 1.22006742356e-06 - dkappa: -1.82636467361e-06 - } - path_point { - x: 586357.191477 - y: 4140746.01541 - theta: 1.30473050978 - kappa: 9.25293691905e-07 - dkappa: -1.84984544107e-06 - } - path_point { - x: 586357.233631 - y: 4140746.17009 - theta: 1.30473063427 - kappa: 6.27278345074e-07 - dkappa: -1.8668036871e-06 - } - path_point { - x: 586357.275786 - y: 4140746.32477 - theta: 1.30473071079 - kappa: 3.27067080816e-07 - dkappa: -1.8772394179e-06 - } - path_point { - x: 586357.31794 - y: 4140746.47945 - theta: 1.30473073908 - kappa: 2.57055961865e-08 - dkappa: -1.88115263728e-06 - } - path_point { - x: 586357.360094 - y: 4140746.63413 - theta: 1.30473071903 - kappa: -2.75760412126e-07 - dkappa: -1.87854334666e-06 - } - path_point { - x: 586357.402249 - y: 4140746.78881 - theta: 1.30473065071 - kappa: -5.76285247463e-07 - dkappa: -1.86941154508e-06 - } - path_point { - x: 586357.444403 - y: 4140746.94349 - theta: 1.30473053435 - kappa: -8.74823212863e-07 - dkappa: -1.85375722916e-06 - } - path_point { - x: 586357.486557 - y: 4140747.09817 - theta: 1.30473037037 - kappa: -1.17032861073e-06 - dkappa: -1.83158039315e-06 - } - path_point { - x: 586357.528712 - y: 4140747.25285 - theta: 1.30473015931 - kappa: -1.46175574253e-06 - dkappa: -1.80288102901e-06 - } - path_point { - x: 586357.570866 - y: 4140747.40753 - theta: 1.30472990194 - kappa: -1.74805890841e-06 - dkappa: -1.7676591264e-06 - } - path_point { - x: 586357.613021 - y: 4140747.56221 - theta: 1.30472959914 - kappa: -2.02819240698e-06 - dkappa: -1.72591467284e-06 - } - path_point { - x: 586357.655175 - y: 4140747.71689 - theta: 1.304729252 - kappa: -2.30111053495e-06 - dkappa: -1.67764765378e-06 - } - path_point { - x: 586357.69733 - y: 4140747.87157 - theta: 1.30472886175 - kappa: -2.56576758688e-06 - dkappa: -1.62285805269e-06 - } - path_point { - x: 586357.739485 - y: 4140748.02625 - theta: 1.30472842981 - kappa: -2.82111785491e-06 - dkappa: -1.5615458513e-06 - } - path_point { - x: 586357.781639 - y: 4140748.18093 - theta: 1.30472795774 - kappa: -3.06611562854e-06 - dkappa: -1.49371102964e-06 - } - path_point { - x: 586357.823794 - y: 4140748.33561 - theta: 1.30472744729 - kappa: -3.2997151944e-06 - dkappa: -1.41935356631e-06 - } - path_point { - x: 586357.865949 - y: 4140748.49029 - theta: 1.30472690038 - kappa: -3.52087083607e-06 - dkappa: -1.33847343865e-06 - } - path_point { - x: 586357.908104 - y: 4140748.64497 - theta: 1.30472631908 - kappa: -3.7285368339e-06 - dkappa: -1.25107062296e-06 - } - path_point { - x: 586357.950259 - y: 4140748.79964 - theta: 1.30472570563 - kappa: -3.92166746493e-06 - dkappa: -1.15714509473e-06 - } - path_point { - x: 586357.992414 - y: 4140748.95432 - theta: 1.30472506246 - kappa: -4.09921700276e-06 - dkappa: -1.05669682893e-06 - } - path_point { - x: 586358.03457 - y: 4140749.109 - theta: 1.30472439214 - kappa: -4.2601397175e-06 - dkappa: -9.49725800228e-07 - } - path_point { - x: 586358.076725 - y: 4140749.26368 - theta: 1.30472369743 - kappa: -4.4033898758e-06 - dkappa: -8.36231983358e-07 - } - path_point { - x: 586358.118881 - y: 4140749.41836 - theta: 1.30472298123 - kappa: -4.52792174082e-06 - dkappa: -7.16215353384e-07 - } - path_point { - x: 586358.161036 - y: 4140749.57304 - theta: 1.30472224664 - kappa: -4.63268957233e-06 - dkappa: -5.89675886055e-07 - } - path_point { - x: 586358.203192 - y: 4140749.72772 - theta: 1.30472149691 - kappa: -4.71664762686e-06 - dkappa: -4.56613558156e-07 - } - path_point { - x: 586358.245348 - y: 4140749.8824 - theta: 1.30472073546 - kappa: -4.77875015782e-06 - dkappa: -3.17028347882e-07 - } - path_point { - x: 586358.287504 - y: 4140750.03708 - theta: 1.30471996587 - kappa: -4.81795141579e-06 - dkappa: -1.7092023523e-07 - } - path_point { - x: 586358.32966 - y: 4140750.19176 - theta: 1.3047191919 - kappa: -4.83320564876e-06 - dkappa: -1.82892024096e-08 - } - path_point { - x: 586358.371816 - y: 4140750.34644 - theta: 1.30471841748 - kappa: -4.8234671025e-06 - dkappa: 1.40864765722e-07 - } - path_point { - x: 586358.413972 - y: 4140750.50111 - theta: 1.30471764669 - kappa: -4.78769002094e-06 - dkappa: 3.06541681215e-07 - } - path_point { - x: 586358.456128 - y: 4140750.65579 - theta: 1.3047168838 - kappa: -4.72482864667e-06 - dkappa: 4.78741552552e-07 - } - path_point { - x: 586358.498285 - y: 4140750.81047 - theta: 1.30471613322 - kappa: -4.63383722146e-06 - dkappa: 6.57464384163e-07 - } - path_point { - x: 586358.540441 - y: 4140750.96515 - theta: 1.30471539956 - kappa: -4.51366998688e-06 - dkappa: 8.42710175918e-07 - } - path_point { - x: 586358.582598 - y: 4140751.11983 - theta: 1.30471468757 - kappa: -4.36328118496e-06 - dkappa: 1.03447892259e-06 - } - path_point { - x: 586358.624755 - y: 4140751.27451 - theta: 1.30471400218 - kappa: -4.18162505896e-06 - dkappa: 1.23277061334e-06 - } - path_point { - x: 586358.666912 - y: 4140751.42919 - theta: 1.3047133485 - kappa: -3.96765585422e-06 - dkappa: 1.43758523109e-06 - } - path_point { - x: 586358.709069 - y: 4140751.58386 - theta: 1.30471273177 - kappa: -3.72032781904e-06 - dkappa: 1.64892275201e-06 - } - path_point { - x: 586358.751226 - y: 4140751.73854 - theta: 1.30471215745 - kappa: -3.43859520569e-06 - dkappa: 1.86678314485e-06 - } - path_point { - x: 586358.793383 - y: 4140751.89322 - theta: 1.30471163111 - kappa: -3.12141227151e-06 - dkappa: 2.09116637038e-06 - } - path_point { - x: 586358.83554 - y: 4140752.0479 - theta: 1.30471115854 - kappa: -2.76773328007e-06 - dkappa: 2.32207238069e-06 - } - path_point { - x: 586358.877698 - y: 4140752.20258 - theta: 1.30471074567 - kappa: -2.37651250243e-06 - dkappa: 2.55950111855e-06 - } - path_point { - x: 586358.919855 - y: 4140752.35726 - theta: 1.3047103986 - kappa: -1.94670421852e-06 - dkappa: 2.80345251674e-06 - } - path_point { - x: 586358.962012 - y: 4140752.51194 - theta: 1.3047101236 - kappa: -1.47726271854e-06 - dkappa: 3.05392649734e-06 - } - path_point { - x: 586359.00417 - y: 4140752.66661 - theta: 1.3047099271 - kappa: -9.67142304608e-07 - dkappa: 3.31092297099e-06 - } - path_point { - x: 586359.046327 - y: 4140752.82129 - theta: 1.30470981572 - kappa: -4.15297292323e-07 - dkappa: 3.57444183619e-06 - } - path_point { - x: 586359.088485 - y: 4140752.97597 - theta: 1.30470979614 - kappa: 1.74520697522e-07 - dkappa: 3.66494059886e-06 - } - path_point { - x: 586359.130642 - y: 4140753.13065 - theta: 1.30470987009 - kappa: 7.40983544854e-07 - dkappa: 3.40275042595e-06 - } - path_point { - x: 586359.1728 - y: 4140753.28533 - theta: 1.30471003151 - kappa: 1.26591960397e-06 - dkappa: 3.14689297415e-06 - } - path_point { - x: 586359.214957 - y: 4140753.44 - theta: 1.30471027383 - kappa: 1.75034415227e-06 - dkappa: 2.89736834819e-06 - } - path_point { - x: 586359.257115 - y: 4140753.59468 - theta: 1.30471059063 - kappa: 2.19527248111e-06 - dkappa: 2.65417664073e-06 - } - path_point { - x: 586359.299272 - y: 4140753.74936 - theta: 1.30471097567 - kappa: 2.60171989422e-06 - dkappa: 2.41731793305e-06 - } - path_point { - x: 586359.341429 - y: 4140753.90404 - theta: 1.30471142285 - kappa: 2.97070170606e-06 - dkappa: 2.18679229576e-06 - } - path_point { - x: 586359.383586 - y: 4140754.05872 - theta: 1.30471192625 - kappa: 3.30323324046e-06 - dkappa: 1.96259978945e-06 - } - path_point { - x: 586359.425743 - y: 4140754.2134 - theta: 1.30471248011 - kappa: 3.60032982919e-06 - dkappa: 1.74474046538e-06 - } - path_point { - x: 586359.467901 - y: 4140754.36808 - theta: 1.30471307882 - kappa: 3.86300681072e-06 - dkappa: 1.53321436611e-06 - } - path_point { - x: 586359.510057 - y: 4140754.52275 - theta: 1.30471371696 - kappa: 4.09227952905e-06 - dkappa: 1.32802152614e-06 - } - path_point { - x: 586359.552214 - y: 4140754.67743 - theta: 1.30471438924 - kappa: 4.2891633326e-06 - dkappa: 1.12916197248e-06 - } - path_point { - x: 586359.594371 - y: 4140754.83211 - theta: 1.30471509056 - kappa: 4.45467357319e-06 - dkappa: 9.36635725252e-07 - } - path_point { - x: 586359.636528 - y: 4140754.98679 - theta: 1.30471581597 - kappa: 4.58982560515e-06 - dkappa: 7.50442798296e-07 - } - path_point { - x: 586359.678684 - y: 4140755.14147 - theta: 1.30471656068 - kappa: 4.69563478443e-06 - dkappa: 5.70583199667e-07 - } - path_point { - x: 586359.720841 - y: 4140755.29615 - theta: 1.30471732007 - kappa: 4.77311646784e-06 - dkappa: 3.97056932202e-07 - } - path_point { - x: 586359.762997 - y: 4140755.45083 - theta: 1.30471808968 - kappa: 4.82328601235e-06 - dkappa: 2.29863994021e-07 - } - path_point { - x: 586359.805153 - y: 4140755.6055 - theta: 1.30471886521 - kappa: 4.84715877447e-06 - dkappa: 6.90043790301e-08 - } - path_point { - x: 586359.847309 - y: 4140755.76018 - theta: 1.30471964253 - kappa: 4.84575010968e-06 - dkappa: -8.55219226027e-08 - } - path_point { - x: 586359.889465 - y: 4140755.91486 - theta: 1.30472041766 - kappa: 4.82007537192e-06 - dkappa: -2.33714923986e-07 - } - path_point { - x: 586359.931621 - y: 4140756.06954 - theta: 1.3047211868 - kappa: 4.77114991319e-06 - dkappa: -3.75574641062e-07 - } - path_point { - x: 586359.973777 - y: 4140756.22422 - theta: 1.3047219463 - kappa: 4.69998908313e-06 - dkappa: -5.11101092184e-07 - } - path_point { - x: 586360.015932 - y: 4140756.3789 - theta: 1.30472269268 - kappa: 4.60760822879e-06 - dkappa: -6.40294297707e-07 - } - path_point { - x: 586360.058088 - y: 4140756.53358 - theta: 1.30472342261 - kappa: 4.49502269427e-06 - dkappa: -7.63154279605e-07 - } - path_point { - x: 586360.100243 - y: 4140756.68826 - theta: 1.30472413294 - kappa: 4.36324782059e-06 - dkappa: -8.79681061092e-07 - } - path_point { - x: 586360.142399 - y: 4140756.84294 - theta: 1.30472482068 - kappa: 4.21329894551e-06 - dkappa: -9.89874666281e-07 - } - path_point { - x: 586360.184554 - y: 4140756.99762 - theta: 1.30472548298 - kappa: 4.04619140343e-06 - dkappa: -1.09373511984e-06 - } - path_point { - x: 586360.226709 - y: 4140757.1523 - theta: 1.30472611719 - kappa: 3.86294052533e-06 - dkappa: -1.19126244669e-06 - } - path_point { - x: 586360.268864 - y: 4140757.30698 - theta: 1.30472672079 - kappa: 3.66456163873e-06 - dkappa: -1.28245667168e-06 - } - path_point { - x: 586360.311019 - y: 4140757.46165 - theta: 1.30472729145 - kappa: 3.45207006777e-06 - dkappa: -1.36731781935e-06 - } - path_point { - x: 586360.353174 - y: 4140757.61633 - theta: 1.30472782697 - kappa: 3.22648113322e-06 - dkappa: -1.44584591362e-06 - } - path_point { - x: 586360.395328 - y: 4140757.77101 - theta: 1.30472832535 - kappa: 2.98881015257e-06 - dkappa: -1.5180409776e-06 - } - path_point { - x: 586360.437483 - y: 4140757.92569 - theta: 1.30472878472 - kappa: 2.74007244023e-06 - dkappa: -1.58390303332e-06 - } - path_point { - x: 586360.479638 - y: 4140758.08037 - theta: 1.30472920339 - kappa: 2.48128330761e-06 - dkappa: -1.64343210154e-06 - } - path_point { - x: 586360.521792 - y: 4140758.23505 - theta: 1.30472957984 - kappa: 2.21345806334e-06 - dkappa: -1.69662820158e-06 - } - path_point { - x: 586360.563947 - y: 4140758.38973 - theta: 1.30472991269 - kappa: 1.93761201351e-06 - dkappa: -1.74349135109e-06 - } - path_point { - x: 586360.606101 - y: 4140758.54441 - theta: 1.30473020074 - kappa: 1.65476046186e-06 - dkappa: -1.78402156599e-06 - } - path_point { - x: 586360.648256 - y: 4140758.69909 - theta: 1.30473044295 - kappa: 1.36591871005e-06 - dkappa: -1.81821886025e-06 - } - path_point { - x: 586360.69041 - y: 4140758.85377 - theta: 1.30473063845 - kappa: 1.07210205797e-06 - dkappa: -1.84608324583e-06 - } - path_point { - x: 586360.732565 - y: 4140759.00845 - theta: 1.3047307865 - kappa: 7.74325803971e-07 - dkappa: -1.86761473253e-06 - } - path_point { - x: 586360.774719 - y: 4140759.16313 - theta: 1.30473088657 - kappa: 4.736052452e-07 - dkappa: -1.88281332797e-06 - } - path_point { - x: 586360.816873 - y: 4140759.31781 - theta: 1.30473093826 - kappa: 1.70955677907e-07 - dkappa: -1.89167903748e-06 - } - path_point { - x: 586360.859028 - y: 4140759.47249 - theta: 1.30473094134 - kappa: -1.32607602242e-07 - dkappa: -1.89421186409e-06 - } - path_point { - x: 586360.901182 - y: 4140759.62717 - theta: 1.30473089574 - kappa: -4.36069299836e-07 - dkappa: -1.89041180847e-06 - } - path_point { - x: 586360.943336 - y: 4140759.78185 - theta: 1.30473080157 - kappa: -7.384141194e-07 - dkappa: -1.88027886896e-06 - } - path_point { - x: 586360.985491 - y: 4140759.93653 - theta: 1.30473065909 - kappa: -1.03862676507e-06 - dkappa: -1.86381304154e-06 - } - path_point { - x: 586361.027645 - y: 4140760.09121 - theta: 1.30473046872 - kappa: -1.33569194025e-06 - dkappa: -1.84101431991e-06 - } - path_point { - x: 586361.069799 - y: 4140760.24589 - theta: 1.30473023104 - kappa: -1.62859434733e-06 - dkappa: -1.81188269548e-06 - } - path_point { - x: 586361.111954 - y: 4140760.40057 - theta: 1.3047299468 - kappa: -1.91631868736e-06 - dkappa: -1.77641815748e-06 - } - path_point { - x: 586361.154108 - y: 4140760.55525 - theta: 1.30472961691 - kappa: -2.19784965974e-06 - dkappa: -1.73462069302e-06 - } - path_point { - x: 586361.196263 - y: 4140760.70993 - theta: 1.30472924246 - kappa: -2.47217196194e-06 - dkappa: -1.68649028721e-06 - } - path_point { - x: 586361.238418 - y: 4140760.86461 - theta: 1.30472882467 - kappa: -2.73827028924e-06 - dkappa: -1.63202692325e-06 - } - path_point { - x: 586361.280572 - y: 4140761.01928 - theta: 1.30472836495 - kappa: -2.99512933447e-06 - dkappa: -1.57123058259e-06 - } - path_point { - x: 586361.322727 - y: 4140761.17396 - theta: 1.30472786486 - kappa: -3.24173378779e-06 - dkappa: -1.5041012451e-06 - } - path_point { - x: 586361.364882 - y: 4140761.32864 - theta: 1.30472732612 - kappa: -3.47706833644e-06 - dkappa: -1.4306388892e-06 - } - path_point { - x: 586361.407037 - y: 4140761.48332 - theta: 1.30472675062 - kappa: -3.70011766463e-06 - dkappa: -1.35084349208e-06 - } - path_point { - x: 586361.449192 - y: 4140761.638 - theta: 1.30472614042 - kappa: -3.90986645331e-06 - dkappa: -1.26471502994e-06 - } - path_point { - x: 586361.491347 - y: 4140761.79268 - theta: 1.30472549772 - kappa: -4.10529938009e-06 - dkappa: -1.17225347814e-06 - } - path_point { - x: 586361.533502 - y: 4140761.94736 - theta: 1.30472482491 - kappa: -4.28540111913e-06 - dkappa: -1.07345881151e-06 - } - path_point { - x: 586361.575657 - y: 4140762.10204 - theta: 1.30472412452 - kappa: -4.44915634112e-06 - dkappa: -9.68331004628e-07 - } - path_point { - x: 586361.617813 - y: 4140762.25672 - theta: 1.30472339925 - kappa: -4.5955497132e-06 - dkappa: -8.56870032026e-07 - } - path_point { - x: 586361.659968 - y: 4140762.4114 - theta: 1.30472265198 - kappa: -4.72356589905e-06 - dkappa: -7.39075868561e-07 - } - path_point { - x: 586361.702124 - y: 4140762.56608 - theta: 1.30472188572 - kappa: -4.83218955892e-06 - dkappa: -6.14948489707e-07 - } - path_point { - x: 586361.74428 - y: 4140762.72076 - theta: 1.30472110367 - kappa: -4.92040534975e-06 - dkappa: -4.84487871893e-07 - } - path_point { - x: 586361.786436 - y: 4140762.87544 - theta: 1.30472030918 - kappa: -4.98719792534e-06 - dkappa: -3.47693992863e-07 - } - path_point { - x: 586361.828592 - y: 4140763.03011 - theta: 1.30471950576 - kappa: -5.03155193656e-06 - dkappa: -2.04566832043e-07 - } - path_point { - x: 586361.870748 - y: 4140763.18479 - theta: 1.30471869711 - kappa: -5.05245203162e-06 - dkappa: -5.51063709399e-08 - } - path_point { - x: 586361.912904 - y: 4140763.33947 - theta: 1.30471788705 - kappa: -5.04888285639e-06 - dkappa: 1.00687406455e-07 - } - path_point { - x: 586361.95506 - y: 4140763.49415 - theta: 1.30471707959 - kappa: -5.01982905478e-06 - dkappa: 2.62814513234e-07 - } - path_point { - x: 586361.997217 - y: 4140763.64883 - theta: 1.3047162789 - kappa: -4.96427526919e-06 - dkappa: 4.3127495913e-07 - } - path_point { - x: 586362.039373 - y: 4140763.80351 - theta: 1.30471548931 - kappa: -4.881206141e-06 - dkappa: 6.06068750053e-07 - } - path_point { - x: 586362.08153 - y: 4140763.95819 - theta: 1.30471471531 - kappa: -4.7696063112e-06 - dkappa: 7.87195887604e-07 - } - path_point { - x: 586362.123687 - y: 4140764.11287 - theta: 1.30471396156 - kappa: -4.62846042093e-06 - dkappa: 9.74656368579e-07 - } - path_point { - x: 586362.165844 - y: 4140764.26754 - theta: 1.30471323287 - kappa: -4.45675311231e-06 - dkappa: 1.16845018445e-06 - } - path_point { - x: 586362.208001 - y: 4140764.42222 - theta: 1.30471253423 - kappa: -4.25346902914e-06 - dkappa: 1.36857732082e-06 - } - path_point { - x: 586362.250158 - y: 4140764.5769 - theta: 1.30471187077 - kappa: -4.01759281781e-06 - dkappa: 1.57503775689e-06 - } - path_point { - x: 586362.292315 - y: 4140764.73158 - theta: 1.30471124782 - kappa: -3.74810912822e-06 - dkappa: 1.78783146487e-06 - } - path_point { - x: 586362.334472 - y: 4140764.88626 - theta: 1.30471067083 - kappa: -3.44400261484e-06 - dkappa: 2.00695840937e-06 - } - path_point { - x: 586362.37663 - y: 4140765.04094 - theta: 1.30471014544 - kappa: -3.10425793776e-06 - dkappa: 2.23241854684e-06 - } - path_point { - x: 586362.418787 - y: 4140765.19561 - theta: 1.30470967744 - kappa: -2.72785976395e-06 - dkappa: 2.46421182489e-06 - } - path_point { - x: 586362.460945 - y: 4140765.35029 - theta: 1.30470927279 - kappa: -2.31379276851e-06 - dkappa: 2.70233818169e-06 - } - path_point { - x: 586362.503102 - y: 4140765.50497 - theta: 1.30470893761 - kappa: -1.86104163606e-06 - dkappa: 2.94679754528e-06 - } - path_point { - x: 586362.54526 - y: 4140765.65965 - theta: 1.30470867818 - kappa: -1.36859106218e-06 - dkappa: 3.19758983287e-06 - } - path_point { - x: 586362.587418 - y: 4140765.81433 - theta: 1.30470850095 - kappa: -8.36338017625e-07 - dkappa: 3.38641599326e-06 - } - path_point { - x: 586362.629575 - y: 4140765.96901 - theta: 1.30470840975 - kappa: -3.05356807337e-07 - dkappa: 3.23806711519e-06 - } - path_point { - x: 586362.671733 - y: 4140766.12368 - theta: 1.30470840178 - kappa: 2.02072069896e-07 - dkappa: 3.09260015646e-06 - } - path_point { - x: 586362.713891 - y: 4140766.27836 - theta: 1.30470847331 - kappa: 6.86410655272e-07 - dkappa: 2.95001517575e-06 - } - path_point { - x: 586362.756048 - y: 4140766.43304 - theta: 1.30470862066 - kappa: 1.14812099798e-06 - dkappa: 2.8103122274e-06 - } - path_point { - x: 586362.798206 - y: 4140766.58772 - theta: 1.30470884026 - kappa: 1.5876651546e-06 - dkappa: 2.67349136157e-06 - } - path_point { - x: 586362.840364 - y: 4140766.7424 - theta: 1.30470912857 - kappa: 2.00550518854e-06 - dkappa: 2.53955262443e-06 - } - path_point { - x: 586362.882521 - y: 4140766.89708 - theta: 1.30470948217 - kappa: 2.40210316946e-06 - dkappa: 2.40849605835e-06 - } - path_point { - x: 586362.924679 - y: 4140767.05175 - theta: 1.30470989767 - kappa: 2.7779211728e-06 - dkappa: 2.28032170203e-06 - } - path_point { - x: 586362.966836 - y: 4140767.20643 - theta: 1.3047103718 - kappa: 3.13342127921e-06 - dkappa: 2.15502959073e-06 - } - path_point { - x: 586363.008993 - y: 4140767.36111 - theta: 1.30471090132 - kappa: 3.46906557416e-06 - dkappa: 2.03261975636e-06 - } - path_point { - x: 586363.051151 - y: 4140767.51579 - theta: 1.30471148308 - kappa: 3.78531614739e-06 - dkappa: 1.91309222772e-06 - } - path_point { - x: 586363.093308 - y: 4140767.67047 - theta: 1.30471211403 - kappa: 4.08263509258e-06 - dkappa: 1.79644703058e-06 - } - path_point { - x: 586363.135465 - y: 4140767.82515 - theta: 1.30471279116 - kappa: 4.36148450684e-06 - dkappa: 1.6826841879e-06 - } - path_point { - x: 586363.177622 - y: 4140767.97982 - theta: 1.30471351154 - kappa: 4.62232649041e-06 - dkappa: 1.57180371993e-06 - } - path_point { - x: 586363.219779 - y: 4140768.1345 - theta: 1.30471427233 - kappa: 4.86562314625e-06 - dkappa: 1.46380564438e-06 - } - path_point { - x: 586363.261936 - y: 4140768.28918 - theta: 1.30471507074 - kappa: 5.09183657966e-06 - dkappa: 1.35868997657e-06 - } - path_point { - x: 586363.304092 - y: 4140768.44386 - theta: 1.30471590409 - kappa: 5.30142889804e-06 - dkappa: 1.25645672953e-06 - } - path_point { - x: 586363.346249 - y: 4140768.59854 - theta: 1.30471676974 - kappa: 5.4948622105e-06 - dkappa: 1.15710591419e-06 - } - path_point { - x: 586363.388405 - y: 4140768.75322 - theta: 1.30471766513 - kappa: 5.67259862761e-06 - dkappa: 1.06063753946e-06 - } - path_point { - x: 586363.430561 - y: 4140768.9079 - theta: 1.30471858779 - kappa: 5.83510026112e-06 - dkappa: 9.67051612383e-07 - } - path_point { - x: 586363.472717 - y: 4140769.06257 - theta: 1.30471953531 - kappa: 5.9828292237e-06 - dkappa: 8.76348138263e-07 - } - path_point { - x: 586363.514873 - y: 4140769.21725 - theta: 1.30472050537 - kappa: 6.11624762872e-06 - dkappa: 7.88527120771e-07 - } - path_point { - x: 586363.557029 - y: 4140769.37193 - theta: 1.30472149569 - kappa: 6.23581759e-06 - dkappa: 7.03588562068e-07 - } - path_point { - x: 586363.599185 - y: 4140769.52661 - theta: 1.30472250411 - kappa: 6.34200122165e-06 - dkappa: 6.21532462916e-07 - } - path_point { - x: 586363.64134 - y: 4140769.68129 - theta: 1.30472352851 - kappa: 6.43526063783e-06 - dkappa: 5.42358822788e-07 - } - path_point { - x: 586363.683496 - y: 4140769.83597 - theta: 1.30472456686 - kappa: 6.51605795262e-06 - dkappa: 4.66067639975e-07 - } - path_point { - x: 586363.725651 - y: 4140769.99065 - theta: 1.30472561719 - kappa: 6.58485527984e-06 - dkappa: 3.92658911684e-07 - } - path_point { - x: 586363.767806 - y: 4140770.14533 - theta: 1.30472667762 - kappa: 6.64211473289e-06 - dkappa: 3.22132634139e-07 - } - path_point { - x: 586363.809961 - y: 4140770.30001 - theta: 1.30472774633 - kappa: 6.68829842466e-06 - dkappa: 2.54488802673e-07 - } - path_point { - x: 586363.852116 - y: 4140770.45469 - theta: 1.3047288216 - kappa: 6.72386846737e-06 - dkappa: 1.89727411821e-07 - } - path_point { - x: 586363.89427 - y: 4140770.60937 - theta: 1.30472990174 - kappa: 6.7492869725e-06 - dkappa: 1.27848455405e-07 - } - path_point { - x: 586363.936425 - y: 4140770.76405 - theta: 1.30473098518 - kappa: 6.76501605064e-06 - dkappa: 6.88519266171e-08 - } - path_point { - x: 586363.978579 - y: 4140770.91873 - theta: 1.3047320704 - kappa: 6.77151781149e-06 - dkappa: 1.27378181028e-08 - } - path_point { - x: 586364.020733 - y: 4140771.07341 - theta: 1.30473315595 - kappa: 6.7692543637e-06 - dkappa: -4.04938779677e-08 - } - path_point { - x: 586364.062887 - y: 4140771.22809 - theta: 1.30473424046 - kappa: 6.75868781488e-06 - dkappa: -9.08431698249e-08 - } - path_point { - x: 586364.105041 - y: 4140771.38277 - theta: 1.30473532265 - kappa: 6.7402802715e-06 - dkappa: -1.38310066032e-07 - } - path_point { - x: 586364.147194 - y: 4140771.53745 - theta: 1.30473640128 - kappa: 6.71449383888e-06 - dkappa: -1.82894575418e-07 - } - path_point { - x: 586364.189348 - y: 4140771.69213 - theta: 1.30473747523 - kappa: 6.68179062113e-06 - dkappa: -2.24596707022e-07 - } - path_point { - x: 586364.231501 - y: 4140771.84681 - theta: 1.3047385434 - kappa: 6.64263272113e-06 - dkappa: -2.63416470027e-07 - } - path_point { - x: 586364.273654 - y: 4140772.00149 - theta: 1.30473960481 - kappa: 6.59748224055e-06 - dkappa: -2.99353873713e-07 - } - path_point { - x: 586364.315807 - y: 4140772.15617 - theta: 1.30474065854 - kappa: 6.54680127978e-06 - dkappa: -3.32408927406e-07 - } - path_point { - x: 586364.35796 - y: 4140772.31085 - theta: 1.30474170372 - kappa: 6.49105193798e-06 - dkappa: -3.62581640428e-07 - } - path_point { - x: 586364.400113 - y: 4140772.46553 - theta: 1.3047427396 - kappa: 6.43069631303e-06 - dkappa: -3.89872022056e-07 - } - path_point { - x: 586364.442265 - y: 4140772.62021 - theta: 1.30474376545 - kappa: 6.36619650159e-06 - dkappa: -4.14280081483e-07 - } - path_point { - x: 586364.484418 - y: 4140772.77489 - theta: 1.30474478067 - kappa: 6.29801459909e-06 - dkappa: -4.35805827782e-07 - } - path_point { - x: 586364.52657 - y: 4140772.92957 - theta: 1.30474578469 - kappa: 6.22661269975e-06 - dkappa: -4.54449269877e-07 - } - path_point { - x: 586364.568722 - y: 4140773.08425 - theta: 1.30474677704 - kappa: 6.15245289661e-06 - dkappa: -4.70210416507e-07 - } - path_point { - x: 586364.610874 - y: 4140773.23893 - theta: 1.30474775731 - kappa: 6.07599728152e-06 - dkappa: -4.83089276213e-07 - } - path_point { - x: 586364.653025 - y: 4140773.39361 - theta: 1.30474872517 - kappa: 5.99770794524e-06 - dkappa: -4.93085857304e-07 - } - path_point { - x: 586364.695177 - y: 4140773.54829 - theta: 1.30474968036 - kappa: 5.91804697742e-06 - dkappa: -5.00200167853e-07 - } - path_point { - x: 586364.737329 - y: 4140773.70297 - theta: 1.3047506227 - kappa: 5.83747646663e-06 - dkappa: -5.04432215673e-07 - } - path_point { - x: 586364.77948 - y: 4140773.85765 - theta: 1.30475155208 - kappa: 5.75645850043e-06 - dkappa: -5.05782008313e-07 - } - path_point { - x: 586364.821631 - y: 4140774.01233 - theta: 1.30475246846 - kappa: 5.67545516539e-06 - dkappa: -5.0424955305e-07 - } - path_point { - x: 586364.863782 - y: 4140774.16702 - theta: 1.3047533719 - kappa: 5.59492854713e-06 - dkappa: -4.99834856885e-07 - } - path_point { - x: 586364.905933 - y: 4140774.3217 - theta: 1.30475426249 - kappa: 5.51534073034e-06 - dkappa: -4.9253792655e-07 - } - path_point { - x: 586364.948084 - y: 4140774.47638 - theta: 1.30475514042 - kappa: 5.43715379887e-06 - dkappa: -4.82358768504e-07 - } - path_point { - x: 586364.990235 - y: 4140774.63106 - theta: 1.30475600597 - kappa: 5.36082983569e-06 - dkappa: -4.69297388949e-07 - } - path_point { - x: 586365.032385 - y: 4140774.78574 - theta: 1.30475685946 - kappa: 5.286830923e-06 - dkappa: -4.53353793841e-07 - } - path_point { - x: 586365.074536 - y: 4140774.94042 - theta: 1.30475770131 - kappa: 5.2156191422e-06 - dkappa: -4.34527988902e-07 - } - path_point { - x: 586365.116686 - y: 4140775.0951 - theta: 1.30475853199 - kappa: 5.14765657399e-06 - dkappa: -4.12819979642e-07 - } - path_point { - x: 586365.158836 - y: 4140775.24978 - theta: 1.30475935206 - kappa: 5.08340529831e-06 - dkappa: -3.88229771384e-07 - } - path_point { - x: 586365.200986 - y: 4140775.40447 - theta: 1.30476016217 - kappa: 5.02332739445e-06 - dkappa: -3.6075736929e-07 - } - path_point { - x: 586365.243136 - y: 4140775.55915 - theta: 1.30476096301 - kappa: 4.96788494103e-06 - dkappa: -3.30402778389e-07 - } - path_point { - x: 586365.285286 - y: 4140775.71383 - theta: 1.30476175536 - kappa: 4.91754001598e-06 - dkappa: -2.97166003615e-07 - } - path_point { - x: 586365.327436 - y: 4140775.86851 - theta: 1.30476254008 - kappa: 4.87275469664e-06 - dkappa: -2.61047049841e-07 - } - path_point { - x: 586365.369585 - y: 4140776.02319 - theta: 1.3047633181 - kappa: 4.83399105968e-06 - dkappa: -2.22045921926e-07 - } - path_point { - x: 586365.411735 - y: 4140776.17787 - theta: 1.30476409041 - kappa: 4.80171118114e-06 - dkappa: -1.80162624756e-07 - } - path_point { - x: 586365.453884 - y: 4140776.33256 - theta: 1.30476485811 - kappa: 4.77637713643e-06 - dkappa: -1.35397163293e-07 - } - path_point { - x: 586365.496033 - y: 4140776.48724 - theta: 1.30476562232 - kappa: 4.75845100027e-06 - dkappa: -8.77495426318e-08 - } - path_point { - x: 586365.538183 - y: 4140776.64192 - theta: 1.30476638429 - kappa: 4.74839484673e-06 - dkappa: -3.72197680518e-08 - } - path_point { - x: 586365.580332 - y: 4140776.7966 - theta: 1.30476714531 - kappa: 4.74667074914e-06 - dkappa: 1.61921549205e-08 - } - path_point { - x: 586365.622481 - y: 4140776.95128 - theta: 1.30476790675 - kappa: 4.75374078009e-06 - dkappa: 7.24862204485e-08 - } - path_point { - x: 586365.664629 - y: 4140777.10597 - theta: 1.30476867006 - kappa: 4.77006701136e-06 - dkappa: 1.31662422318e-07 - } - path_point { - x: 586365.706778 - y: 4140777.26065 - theta: 1.30476943676 - kappa: 4.79611151389e-06 - dkappa: 1.93720753865e-07 - } - path_point { - x: 586365.748927 - y: 4140777.41533 - theta: 1.30477020845 - kappa: 4.83233635766e-06 - dkappa: 2.58661207904e-07 - } - path_point { - x: 586365.791075 - y: 4140777.57001 - theta: 1.30477098679 - kappa: 4.87920361166e-06 - dkappa: 3.26483776645e-07 - } - path_point { - x: 586365.833223 - y: 4140777.7247 - theta: 1.30477177353 - kappa: 4.9371753438e-06 - dkappa: 3.97188451616e-07 - } - path_point { - x: 586365.875372 - y: 4140777.87938 - theta: 1.30477257048 - kappa: 5.00671362074e-06 - dkappa: 4.70775223573e-07 - } - path_point { - x: 586365.91752 - y: 4140778.03406 - theta: 1.30477337954 - kappa: 5.08828050787e-06 - dkappa: 5.47244082414e-07 - } - path_point { - x: 586365.959668 - y: 4140778.18874 - theta: 1.30477420267 - kappa: 5.18233806911e-06 - dkappa: 6.26595017083e-07 - } - path_point { - x: 586366.001816 - y: 4140778.34343 - theta: 1.30477504192 - kappa: 5.28934836682e-06 - dkappa: 7.08828015477e-07 - } - path_point { - x: 586366.043963 - y: 4140778.49811 - theta: 1.30477589939 - kappa: 5.40977346159e-06 - dkappa: 7.9394306434e-07 + z: 0 + theta: 1.3169659462999999 + kappa: 4.2920755866244524e-21 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586347.92423231073 + y: 4140711.978476244 + z: 0 + theta: 1.3161861268070609 + kappa: -0.0021287984056322469 + s: 0.69644872561660831 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586348.10027104651 + y: 4140712.6522972835 + z: 0 + theta: 1.3141470824466959 + kappa: -0.0036273609621609803 + s: 1.3928856788037836 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586348.27798522415 + y: 4140713.3256612457 + z: 0 + theta: 1.3112646505232286 + kappa: -0.0045620309759745094 + s: 2.089306065164227 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586348.45781472884 + y: 4140713.9984483621 + z: 0 + theta: 1.3079085100262153 + kappa: -0.0049990421845289177 + s: 2.7857119487673487 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586348.63996632257 + y: 4140714.6706024567 + z: 0 + theta: 1.3044021245046116 + kappa: -0.0050043186715633594 + s: 3.4821100604326869 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586348.8244451877 + y: 4140715.3421222726 + z: 0 + theta: 1.3010239186872106 + kappa: -0.0046417566928456831 + s: 4.1785088792514289 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.01108427555 + y: 4140716.013053433 + z: 0 + theta: 1.298007167410093 + kappa: -0.0039772500542448672 + s: 4.8749159234280066 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.1995752299 + y: 4140716.6834800146 + z: 0 + theta: 1.2955389997284463 + kappa: -0.0030771225057289265 + s: 5.5713357975549247 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.389499625 + y: 4140717.353516046 + z: 0 + theta: 1.2937604870742776 + kappa: -0.0020076725276782868 + s: 6.2677692539684875 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.58035958267 + y: 4140718.0232971748 + z: 0 + theta: 1.2927665146249545 + kappa: -0.00083510194941544458 + s: 6.9642132819112188 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.77160891565 + y: 4140718.6929721986 + z: 0 + theta: 1.2926058740508637 + kappa: 0.00037447645547263595 + s: 7.66066209181139 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586349.96268412052 + y: 4140719.3626946341 + z: 0 + theta: 1.2932813618953674 + kappa: 0.001554978831132473 + s: 8.3571086974957929 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586350.15303528891 + y: 4140720.0326143028 + z: 0 + theta: 1.2947496863166492 + kappa: 0.0026403079056776021 + s: 9.0535467276285129 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586350.34215714072 + y: 4140720.7028688835 + z: 0 + theta: 1.2969214878619191 + kappa: 0.003564294306149044 + s: 9.7499720845415521 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586350.52961992682 + y: 4140721.3735754951 + z: 0 + theta: 1.2996613225021321 + kappa: 0.0042606717680658433 + s: 10.446384071087293 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586350.71510048548 + y: 4140722.0448222337 + z: 0 + theta: 1.30278758063145 + kappa: 0.0046631288386760478 + s: 11.142785694990446 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586350.89841318084 + y: 4140722.71665973 + z: 0 + theta: 1.3060725069787704 + kappa: 0.0047053707335124 + s: 11.839182970582813 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.07954080915 + y: 4140723.3890927243 + z: 0 + theta: 1.309242222205496 + kappa: 0.0043211878075734358 + s: 12.535583250443215 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.25866569637 + y: 4140724.0620715762 + z: 0 + theta: 1.3119767698009186 + kappa: 0.0034445009900012139 + s: 13.231992799763816 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.43620057649 + y: 4140724.7354838392 + z: 0 + theta: 1.3139101730966187 + kappa: 0.0020097085427812772 + s: 13.928414158941914 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.612797423 + y: 4140725.4091518433 + z: 0 + theta: 1.31475868134289 + kappa: 0.00048811801994844389 + s: 14.624844360733746 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.78915222234 + y: 4140726.0828859005 + z: 0 + theta: 1.3146713178405633 + kappa: -0.000683395440409698 + s: 15.321277124974163 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586351.96581447218 + y: 4140726.756536229 + z: 0 + theta: 1.3138804733957539 + kappa: -0.0015375963898534505 + s: 16.017706816798533 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586352.14318516641 + y: 4140727.429993513 + z: 0 + theta: 1.3125957371760437 + kappa: -0.00210725669840767 + s: 16.714129875387957 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586352.32153215748 + y: 4140728.1031847214 + z: 0 + theta: 1.3110036688827718 + kappa: -0.0024258386058544188 + s: 17.4105450190212 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586352.50100575527 + y: 4140728.7760688658 + z: 0 + theta: 1.3092676468840931 + kappa: -0.0025261479954626085 + s: 18.106952833471347 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586352.68165414978 + y: 4140729.4486328084 + z: 0 + theta: 1.307528334732706 + kappa: -0.002440747196430856 + s: 18.803355087449024 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586352.86343860277 + y: 4140730.1208871137 + z: 0 + theta: 1.3059037123539694 + kappa: -0.0022022290175672146 + s: 19.499753994962788 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.046248791 + y: 4140730.79286186 + z: 0 + theta: 1.3044890539004124 + kappa: -0.0018431895466376152 + s: 20.196151599968427 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.22991799959 + y: 4140731.4646024918 + z: 0 + theta: 1.3033569368990605 + kappa: -0.0013962344204433766 + s: 20.892549370571242 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.41423834232 + y: 4140732.1361656711 + z: 0 + theta: 1.3025572217675006 + kappa: -0.000893972731825607 + s: 21.5889480297051 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.59897610254 + y: 4140732.8076150934 + z: 0 + theta: 1.3021170820697945 + kappa: -0.00036899999486144616 + s: 22.285347603839512 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.7838869082 + y: 4140733.4790173536 + z: 0 + theta: 1.3020409890516156 + kappa: 0.00014609017684769844 + s: 22.981747633310039 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586353.96873100952 + y: 4140734.1504377858 + z: 0 + theta: 1.3023106972859297 + kappa: 0.00061870660709611384 + s: 23.678147474288185 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586354.15328853729 + y: 4140734.8219363042 + z: 0 + theta: 1.3028852926907879 + kappa: 0.0010162569676233351 + s: 24.374546599301723 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586354.33737473644 + y: 4140735.4935632595 + z: 0 + theta: 1.3037011489488801 + kappa: 0.0013061433787793526 + s: 25.070944830032008 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586354.52085526835 + y: 4140736.1653552651 + z: 0 + theta: 1.3046719264582016 + kappa: 0.0014557710275326017 + s: 25.767342420816647 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586354.70366136741 + y: 4140736.8373310696 + z: 0 + theta: 1.3056886093415256 + kappa: 0.0014325372589602771 + s: 26.463739973712766 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586354.885805177 + y: 4140737.5094873742 + z: 0 + theta: 1.3066194655102503 + kappa: 0.001203847708632987 + s: 27.160138182483891 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.06739500584 + y: 4140738.18179467 + z: 0 + theta: 1.3073100802130755 + kappa: 0.00073777612478194616 + s: 27.856537468676692 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.24864068883 + y: 4140738.8541957769 + z: 0 + theta: 1.3076385509893127 + kappa: 0.00022590804867018581 + s: 28.552937674152165 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.42977611918 + y: 4140739.5266269506 + z: 0 + theta: 1.3076518126331713 + kappa: -0.00016924780257235623 + s: 29.249338225227369 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.6109866167 + y: 4140740.1990376795 + z: 0 + theta: 1.3074274381457789 + kappa: -0.00045841426766340065 + s: 29.945738564626332 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.79240794107 + y: 4140740.8713909537 + z: 0 + theta: 1.3070351908269089 + kappa: -0.00065335347120357634 + s: 30.642138322130315 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586355.97413173981 + y: 4140741.5436617872 + z: 0 + theta: 1.3065367166175204 + kappa: -0.00076526781824742026 + s: 31.338537354742744 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586356.15621077653 + y: 4140742.2158357967 + z: 0 + theta: 1.3059861189917648 + kappa: -0.00080484317095488953 + s: 32.034935713911409 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586356.33866400912 + y: 4140742.8879078156 + z: 0 + theta: 1.3054300511459491 + kappa: -0.00078275277808693923 + s: 32.731333574873574 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586356.52148150536 + y: 4140743.5598805556 + z: 0 + theta: 1.3049077386456158 + kappa: -0.0007096824887863443 + s: 33.427731162608666 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586356.7046294827 + y: 4140744.2317632264 + z: 0 + theta: 1.3044509611581292 + kappa: -0.00059631615401422016 + s: 34.124128681972664 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586356.888055336 + y: 4140744.9035701691 + z: 0 + theta: 1.3040840677925321 + kappa: -0.00045333254057670268 + s: 34.820526278081715 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.07169256406 + y: 4140745.5753195076 + z: 0 + theta: 1.3038239586377873 + kappa: -0.00029141663799486447 + s: 35.516924013092549 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.25546582427 + y: 4140746.2470317748 + z: 0 + theta: 1.3036800967623954 + kappa: -0.00012125034738625502 + s: 36.213321874299538 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.43929591449 + y: 4140746.9187285546 + z: 0 + theta: 1.3036545173760938 + kappa: 4.64847629189553e-05 + s: 36.909719796496972 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.62310476485 + y: 4140747.5904311202 + z: 0 + theta: 1.3037417989569651 + kappa: 0.00020110655743979769 + s: 37.606117692916328 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.80682044651 + y: 4140748.2621590723 + z: 0 + theta: 1.3039290917395272 + kappa: 0.00033193349393148075 + s: 38.302515491086574 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586357.99038214888 + y: 4140748.9339289847 + z: 0 + theta: 1.3041961107615183 + kappa: 0.000428281389165569 + s: 38.998913160327284 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586358.17374522542 + y: 4140749.605753025 + z: 0 + theta: 1.3045151191843054 + kappa: 0.00047947094482568396 + s: 39.695310718505809 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586358.3568861339 + y: 4140750.2776376121 + z: 0 + theta: 1.3048509519876195 + kappa: 0.00047481878376486405 + s: 40.391708227587444 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586358.539807454 + y: 4140750.9495820473 + z: 0 + theta: 1.3051609996360458 + kappa: 0.00040363914178883449 + s: 41.088105767333616 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586358.72254293528 + y: 4140751.6215771344 + z: 0 + theta: 1.3053952281591998 + kappa: 0.00025572814318325636 + s: 41.7845033930906 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586358.90515892336 + y: 4140752.293604794 + z: 0 + theta: 1.3055152693028687 + kappa: 9.5331438869699682e-05 + s: 42.48090110587448 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586359.08772888838 + y: 4140752.9656450017 + z: 0 + theta: 1.3055364281619157 + kappa: -2.8755799419727913e-05 + s: 43.177298860751108 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586359.27031105477 + y: 4140753.637681888 + z: 0 + theta: 1.30548269653855 + kappa: -0.00012057540162664389 + s: 43.873696609110034 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586359.45294853032 + y: 4140754.3097036993 + z: 0 + theta: 1.3053750933856021 + kappa: -0.00018398233525930151 + s: 44.570094313314364 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586359.63567111839 + y: 4140754.9817023124 + z: 0 + theta: 1.3052323114811308 + kappa: -0.00022211797710088192 + s: 45.266491958435168 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586359.81849675218 + y: 4140755.6536728386 + z: 0 + theta: 1.3050708604884163 + kappa: -0.0002381330493224995 + s: 45.962889546370462 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.00143307843 + y: 4140756.3256131955 + z: 0 + theta: 1.3049050496406682 + kappa: -0.00023516066641780689 + s: 46.659287092871075 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.18447883124 + y: 4140756.9975237283 + z: 0 + theta: 1.3047470109074659 + kappa: -0.00021634275505925601 + s: 47.355684617021772 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.36762529472 + y: 4140757.6694068145 + z: 0 + theta: 1.3046066745173039 + kappa: -0.00018482634296969978 + s: 48.052082138998877 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.550857878 + y: 4140758.3412664309 + z: 0 + theta: 1.3044918021157432 + kappa: -0.00014374739423536132 + s: 48.74847967185238 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.73415747273 + y: 4140759.013107785 + z: 0 + theta: 1.3044079586698416 + kappa: -9.6248877531065463e-05 + s: 49.444877221029266 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586360.91750197159 + y: 4140759.6849369016 + z: 0 + theta: 1.3043585071994226 + kappa: -4.5472987880927127e-05 + s: 50.141274784982663 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586361.10086774291 + y: 4140760.3567602197 + z: 0 + theta: 1.3043446515985027 + kappa: 5.4395911547174779e-06 + s: 50.837672355953806 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586361.28423108114 + y: 4140761.0285841995 + z: 0 + theta: 1.3043653896162191 + kappa: 5.3346620935304443e-05 + s: 51.534069924639169 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586361.46756970952 + y: 4140761.7004149123 + z: 0 + theta: 1.3044175262080415 + kappa: 9.5109129071903746e-05 + s: 52.230467483037032 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586361.65086418751 + y: 4140762.372257655 + z: 0 + theta: 1.3044956979441569 + kappa: 0.0001275824914295082 + s: 52.926865025102693 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586361.8340994498 + y: 4140763.0441165343 + z: 0 + theta: 1.3045923384243823 + kappa: 0.00014762601372491884 + s: 53.623262551665043 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.01726626 + y: 4140763.7159940689 + z: 0 + theta: 1.3046976984384138 + kappa: 0.00015210227632104215 + s: 54.319660068784131 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.200362617 + y: 4140764.3878908055 + z: 0 + theta: 1.3047998402824454 + kappa: 0.00013786354396034219 + s: 55.016057585019716 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.38339532155 + y: 4140765.0598048917 + z: 0 + theta: 1.3048846449717146 + kappa: 0.00010199422159203029 + s: 55.71245510811432 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.56638035667 + y: 4140765.7317319722 + z: 0 + theta: 1.3049413188795702 + kappa: 6.2201282992474082e-05 + s: 56.408852641548677 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.74933597527 + y: 4140766.4036670728 + z: 0 + theta: 1.304973114455759 + kappa: 3.0280409744126634e-05 + s: 57.105250184450874 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586362.93227717117 + y: 4140767.0756061058 + z: 0 + theta: 1.3049850156543403 + kappa: 4.9478071855930641e-06 + s: 57.801647732795374 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586363.11521581269 + y: 4140767.7475458351 + z: 0 + theta: 1.3049813962981478 + kappa: -1.4403585003080934e-05 + s: 58.498045281830244 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586363.29816099547 + y: 4140768.4194837818 + z: 0 + theta: 1.3049662067315051 + kappa: -2.8364849717711773e-05 + s: 59.194442829293 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586363.48111925507 + y: 4140769.0914181634 + z: 0 + theta: 1.3049430001386932 + kappa: -3.7533911700764208e-05 + s: 59.890840372310905 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586363.66409490665 + y: 4140769.7633478041 + z: 0 + theta: 1.30491490528064 + kappa: -4.250458944882124e-05 + s: 60.587237910442838 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586363.84709032439 + y: 4140770.4352720566 + z: 0 + theta: 1.304884637398068 + kappa: -4.3869597621376122e-05 + s: 61.283635443500742 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.030106135 + y: 4140771.1071907505 + z: 0 + theta: 1.3048545016124766 + kappa: -4.2225994742072123e-05 + s: 61.980032972335309 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.2131416077 + y: 4140771.7791040852 + z: 0 + theta: 1.30482638576074 + kappa: -3.8167207527520629e-05 + s: 62.676430497852621 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.396194887 + y: 4140772.4510125662 + z: 0 + theta: 1.3048017659095512 + kappa: -3.2287210124595144e-05 + s: 63.372828020797058 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.57926320494 + y: 4140773.1229169485 + z: 0 + theta: 1.3047817007697482 + kappa: -2.5181821179363886e-05 + s: 64.0692255423198 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.76234328514 + y: 4140773.7948181261 + z: 0 + theta: 1.3047668384889164 + kappa: -1.7444829972625523e-05 + s: 64.765623064031132 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586364.94543154282 + y: 4140774.4667170746 + z: 0 + theta: 1.304757413064058 + kappa: -9.6710936841497046e-06 + s: 65.462020584910292 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586365.12852432521 + y: 4140775.1386147905 + z: 0 + theta: 1.3047532396222445 + kappa: -2.4548147619652409e-06 + s: 66.1584181061438 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586365.311618309 + y: 4140775.8105121781 + z: 0 + theta: 1.3047537255025263 + kappa: 3.609103513087464e-06 + s: 66.854815626503452 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586365.49471068615 + y: 4140776.4824100044 + z: 0 + theta: 1.3047578609145267 + kappa: 7.9252977144650644e-06 + s: 67.5512131476724 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586365.677799423 + y: 4140777.1543088229 + z: 0 + theta: 1.3047642214040458 + kappa: 9.9015576113753617e-06 + s: 68.247610669178954 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586365.86088365165 + y: 4140777.826208869 + z: 0 + theta: 1.3047709700336565 + kappa: 8.9411150301800169e-06 + s: 68.944008189763338 + dkappa: 0 + ddkappa: 0 + } + path_point { + x: 586366.04396385 + y: 4140778.498110014 + z: 0 + theta: 1.3047758526839264 + kappa: 4.4484759760326277e-06 + s: 69.640405711089173 + dkappa: 0 + ddkappa: 0 } } adc_position { @@ -11044,14 +1065,14 @@ debug { } chassis { engine_started: true - engine_rpm: 0.0 - speed_mps: 5.44722223282 - odometer_m: 0.0 + engine_rpm: 0 + speed_mps: 5.4472222 + odometer_m: 0 fuel_range_m: 0 - throttle_percentage: 15.1781492233 - brake_percentage: 20.2838172913 - steering_percentage: 0.0425531901419 - steering_torque_nm: 0.0 + throttle_percentage: 15.178149 + brake_percentage: 20.283817 + steering_percentage: 0.04255319 + steering_torque_nm: 0 parking_brake: false driving_mode: COMPLETE_AUTO_DRIVE error_code: NO_ERROR @@ -11077,19 +1098,19 @@ debug { passage_region { segment { id: "1_-1" - start_s: 0.0 - end_s: 153.0 + start_s: 0 + end_s: 153 } } } } measurement { - distance: 153.0 + distance: 153 } routing_request { start { id: "1_-1" - s: 0.0 + s: 0 pose { x: 586392.84003 y: 4140673.01232 @@ -11097,7 +1118,7 @@ debug { } end { id: "1_-1" - s: 153.0 + s: 153 pose { x: 586367.70649 y: 4140785.35795 @@ -11111,7 +1132,7 @@ debug { st_graph { name: "QP_SPLINE_ST_SPEED_OPTIMIZER" speed_limit { - s: 0.0 + s: 0 v: 4.5 } speed_limit { -- GitLab