提交 89ea6e43 编写于 作者: L Liangliang Zhang 提交者: Dong Li

Planning: use piecewise linear method to solve qp problem when spline (#493)

fails. fixed init point printout bug.
上级 68da6727
......@@ -55,6 +55,12 @@ Status VehicleState::Update(
InitAdcBoundingBox();
ADEBUG << x_ << ", " << y_ << ", " << z_ << ", " << roll_ << ", " << pitch_
<< ", " << yaw_ << ", " << heading_ << ", " << kappa_ << ", "
<< linear_v_ << ", " << angular_v_ << ", " << timestamp_ << ", "
<< linear_a_y_ << ", " << pose_.ShortDebugString() << ", "
<< adc_bounding_box_->DebugString();
return Status::OK();
}
......
......@@ -134,18 +134,16 @@ DEFINE_bool(enable_rule_layer, true,
/// common
DEFINE_double(stop_max_distance_buffer, 4.0,
"distance buffer of passing stop line");
DEFINE_double(stop_min_speed, 0.1,
"min speed for computing stop");
DEFINE_double(stop_max_deceleration, 6.0,
"max deceleration");
DEFINE_double(stop_min_speed, 0.1, "min speed for computing stop");
DEFINE_double(stop_max_deceleration, 6.0, "max deceleration");
/// traffic light
DEFINE_bool(enable_signal_lights, false, "enable signal_lights");
DEFINE_string(signal_light_virtual_object_id_prefix, "SL_",
"prefix for converting signal id to virtual object id");
DEFINE_double(max_deacceleration_for_yellow_light_stop, 2.0,
"treat yellow light as red when deceleration (abstract value"
" in m/s^2) is less than this threshold; otherwise treated"
" as green light");
" in m/s^2) is less than this threshold; otherwise treated"
" as green light");
/// crosswalk
DEFINE_bool(enable_crosswalk, false, "enable crosswalk");
DEFINE_string(crosswalk_virtual_object_id_prefix, "CW_",
......
......@@ -107,7 +107,7 @@ em_planner_config {
qp_piecewise_config {
number_of_evaluated_graph_t: 40
accel_kernel_weight: 1000.0
jerk_kernel_weight: 500.0
jerk_kernel_weight: 0.0
follow_weight: 8.0
stop_weight: 0.2
cruise_weight: 0.1
......
......@@ -62,6 +62,11 @@ bool QpSplinePathGenerator::Generate(
const std::vector<const PathObstacle*>& path_obstacles,
const SpeedData& speed_data, const common::TrajectoryPoint& init_point,
PathData* const path_data) {
knots_.clear();
evaluated_s_.clear();
ADEBUG << "Init point: " << init_point.DebugString();
if (!CalculateInitFrenetPoint(init_point, &init_frenet_point_)) {
AERROR << "Fail to map init point: " << init_point.ShortDebugString();
return false;
......
......@@ -68,17 +68,16 @@ void QpPiecewiseStGraph::SetDebugLogger(
Status QpPiecewiseStGraph::Search(
const StGraphData& st_graph_data, SpeedData* const speed_data,
const std::pair<double, double>& accel_bound) {
ADEBUG << init_point_.DebugString();
cruise_.clear();
init_point_ = st_graph_data.init_point();
ADEBUG << "Init point:" << init_point_.DebugString();
// reset piecewise linear generator
generator_.reset(new PiecewiseLinearGenerator(
qp_st_speed_config_.qp_piecewise_config().number_of_evaluated_graph_t(),
t_evaluated_resolution_));
// start to search for best st points
init_point_ = st_graph_data.init_point();
if (!ApplyConstraint(st_graph_data.init_point(), st_graph_data.speed_limit(),
st_graph_data.st_boundaries(), accel_bound)
.ok()) {
......
......@@ -82,13 +82,13 @@ Status QpSplineStGraph::Search(const StGraphData& st_graph_data,
const std::pair<double, double>& accel_bound) {
cruise_.clear();
init_point_ = st_graph_data.init_point();
ADEBUG << "init point:" << init_point_.DebugString();
// reset spline generator
spline_generator_.reset(new Spline1dGenerator(
t_knots_, qp_st_speed_config_.qp_spline_config().spline_order()));
// start to search for best st points
init_point_ = st_graph_data.init_point();
if (!ApplyConstraint(st_graph_data.init_point(), st_graph_data.speed_limit(),
st_graph_data.st_boundaries(), accel_bound)
.ok()) {
......@@ -142,7 +142,6 @@ Status QpSplineStGraph::ApplyConstraint(
AERROR << msg;
return Status(ErrorCode::PLANNING_ERROR, msg);
}
ADEBUG << "init point constraint:" << init_point.DebugString();
if (!constraint->AddPointDerivativeConstraint(0.0, init_point_.v())) {
const std::string msg = "add st start point velocity constraint failed!";
AERROR << msg;
......
......@@ -121,7 +121,8 @@ Status QpSplineStSpeedOptimizer::Process(const SLBoundary& adc_sl_boundary,
accel_bound.first = qp_st_speed_config_.min_deceleration();
accel_bound.second = qp_st_speed_config_.max_acceleration();
ret = st_graph.Search(st_graph_data, speed_data, accel_bound);
QpPiecewiseStGraph piecewise_st_graph(qp_st_speed_config_, veh_param);
ret = piecewise_st_graph.Search(st_graph_data, speed_data, accel_bound);
if (ret != Status::OK()) {
std::string msg = common::util::StrCat(
......
......@@ -7,1694 +7,1694 @@ trajectory_point {
path_point {
x: 586343.905893
y: 4140690.05199
z: 0
theta: 1.6602776953500005
kappa: -2.5996435455821707e-18
s: 6.3527471044072525e-22
kappa: -2.5996221356251808e-18
dkappa: 0
ddkappa: 0
}
v: 4.2611112594604492
a: 1.04254925048
a: 1.29254925048
relative_time: 0
}
trajectory_point {
path_point {
x: 586343.88760696992
y: 4140690.2653398681
theta: 1.6571258991205793
kappa: -0.0072166551289949707
s: 0.21413207413822577
x: 586343.88912376971
y: 4140690.2476428058
theta: 1.6573873393558123
kappa: -0.006618044035270971
s: 0.19637012863714939
dkappa: 0
ddkappa: 0
}
v: 4.2997339250071835
a: 0.50998778760026764
v: 4.1498750305546288
a: 0.12012464094786379
relative_time: 0.05
}
trajectory_point {
path_point {
x: 586343.86921126279
y: 4140690.4799693795
theta: 1.653955134205219
kappa: -0.01447659474310399
s: 0.429548482418766
x: 586343.87235453934
y: 4140690.4432956111
theta: 1.654496925000692
kappa: -0.01323608807054194
s: 0.39274025727429879
dkappa: 0
ddkappa: 0
}
v: 4.3128592120855753
a: 0.022376756626495631
v: 4.0386388016488084
a: -1.0522999685842724
relative_time: 0.1
}
trajectory_point {
path_point {
x: 586343.85081000836
y: 4140690.6946636122
theta: 1.6507834119165985
kappa: -0.021738723627493867
s: 0.6450298505702865
x: 586343.855585309
y: 4140690.6389484168
theta: 1.6516065005794331
kappa: -0.019854132105812911
s: 0.58911038591144826
dkappa: 0
ddkappa: 0
}
v: 4.3026930390229507
a: -0.42194797316018851
v: 3.927402572742988
a: -2.2247245781164082
relative_time: 0.15000000000000002
}
trajectory_point {
path_point {
x: 586343.83249809523
y: 4140690.908315469
theta: 1.6476271509133456
kappa: -0.028965593642492061
s: 0.85946502007442049
x: 586343.8401966939
y: 4140690.8184930733
theta: 1.6489540780628755
kappa: -0.025927310766333856
s: 0.76931330817170474
dkappa: 0
ddkappa: 0
}
v: 4.2713581176106938
a: -0.82465053247865661
v: 3.8196211968970353
a: -2.2016922243839558
relative_time: 0.2
}
trajectory_point {
path_point {
x: 586343.81952180516
y: 4140691.1202981169
theta: 1.6391252273606738
kappa: -0.034226076519194265
s: 1.0718468878389724
x: 586343.8268816527
y: 4140690.9981890582
theta: 1.6441417191130991
kappa: -0.031238135901758515
s: 0.94951623043196121
dkappa: 0
ddkappa: 0
}
v: 4.2208939531042411
a: -1.1873950520477812
v: 3.711839821051083
a: -2.1786598706515039
relative_time: 0.25
}
trajectory_point {
path_point {
x: 586343.80692227138
y: 4140691.3293401152
theta: 1.6305363686684153
kappa: -0.03934121768728991
s: 1.2812682458711195
x: 586343.81604000379
y: 4140691.1780655482
theta: 1.636751838426554
kappa: -0.035639613358146138
s: 1.1297191526922177
dkappa: 0
ddkappa: 0
}
v: 4.1532568442230895
a: -1.5118456625864343
v: 3.6040584452051303
a: -2.1556275169190515
relative_time: 0.3
}
trajectory_point {
path_point {
x: 586343.79454967333
y: 4140691.534616963
theta: 1.6221020551328609
kappa: -0.044364227730519581
s: 1.4869176209506156
x: 586343.8061385015
y: 4140691.3423438342
theta: 1.6300020699510633
kappa: -0.039659411441800747
s: 1.2942955633971021
dkappa: 0
ddkappa: 0
}
v: 4.0703198831507912
a: -1.7996664948134886
v: 3.4998817015026491
a: -2.1315966359625769
relative_time: 0.35
}
trajectory_point {
path_point {
x: 586343.782447323
y: 4140691.7354100659
theta: 1.6138529806003894
kappa: -0.049277523037102984
s: 1.6880751143029928
x: 586343.79623699922
y: 4140691.50662212
theta: 1.6232522579690014
kappa: -0.043679209525455349
s: 1.4588719741019862
dkappa: 0
ddkappa: 0
}
v: 3.9738729555349535
a: -2.0525216794478149
v: 3.3957049578001675
a: -2.1075657550061018
relative_time: 0.39999999999999997
}
trajectory_point {
path_point {
x: 586343.77684093523
y: 4140691.9313234249
theta: 1.6037058503801069
kappa: -0.052077374706173435
s: 1.8841082412727663
x: 586343.78633549693
y: 4140691.6709004063
theta: 1.616503017472209
kappa: -0.047699007609109959
s: 1.6234483848068706
dkappa: 0
ddkappa: 0
}
v: 3.8656227404872405
a: -2.2720753472082875
v: 3.2915282140976863
a: -2.0835348740496271
relative_time: 0.44999999999999996
}
trajectory_point {
path_point {
x: 586343.77382752683
y: 4140692.1216591019
theta: 1.5930205074935324
kappa: -0.054015130450414853
s: 2.0744677709966339
x: 586343.77860039938
y: 4140691.8201905261
theta: 1.6099431056489397
kappa: -0.050945960897110842
s: 1.7729614152312003
dkappa: 0
ddkappa: 0
}
v: 3.7471927105833744
a: -2.4599916288137775
v: 3.1911056788939898
a: -2.0585068173910623
relative_time: 0.49999999999999994
}
trajectory_point {
path_point {
x: 586343.77091137436
y: 4140692.3058518143
theta: 1.5826785306820357
kappa: -0.05589034634117783
s: 2.2586835660766837
x: 586343.77623359475
y: 4140691.969684822
theta: 1.6015525041744623
kappa: -0.052467921651920171
s: 1.92247444565553
dkappa: 0
ddkappa: 0
}
v: 3.6201231318631315
a: -2.617934654983157
v: 3.0906831436902928
a: -2.0334787607324976
relative_time: 0.54999999999999993
}
trajectory_point {
path_point {
x: 586343.76809873385
y: 4140692.4835064067
theta: 1.5727043529337217
kappa: -0.057698999415573347
s: 2.4363604222535922
x: 586343.77386679023
y: 4140692.119179118
theta: 1.5931597477103174
kappa: -0.053989882406729493
s: 2.07198747607986
dkappa: 0
ddkappa: 0
}
v: 3.4858710638303458
a: -2.747568556435299
v: 2.9902606084865964
a: -2.0084507040739328
relative_time: 0.6
}
trajectory_point {
path_point {
x: 586343.7653947412
y: 4140692.654298489
theta: 1.5631179783654539
kappa: -0.059437787139171014
s: 2.6071739080798277
x: 586343.771729171
y: 4140692.2541973875
theta: 1.5855788203623622
kappa: -0.055364466677187814
s: 2.2070226661794812
dkappa: 0
ddkappa: 0
}
v: 3.3458103594529072
a: -2.8505574638890749
v: 2.8937416729885386
a: -1.9824267060363394
relative_time: 0.65
}
trajectory_point {
path_point {
x: 586343.76948533219
y: 4140692.8178979354
theta: 1.5533704608292087
kappa: -0.059856229523420075
s: 2.7708662045928576
x: 586343.769591552
y: 4140692.3892156575
theta: 1.5779979704364464
kappa: -0.056739050947646127
s: 2.3420578562791023
dkappa: 0
ddkappa: 0
}
v: 3.201231665162763
a: -2.9285655080633575
v: 2.7972227374904808
a: -1.956402707998746
relative_time: 0.70000000000000007
}
trajectory_point {
path_point {
x: 586343.775345266
y: 4140692.9741638415
theta: 1.5438909204906957
kappa: -0.059891393598116335
s: 2.9272419449883458
x: 586343.76745393279
y: 4140692.524233927
theta: 1.5704180691499618
kappa: -0.058113635218104455
s: 2.477093046378724
dkappa: 0
ddkappa: 0
}
v: 3.0533424208559148
a: -2.9832568196770182
v: 2.7007038019924234
a: -1.9303787099611529
relative_time: 0.75000000000000011
}
trajectory_point {
path_point {
x: 586343.78092588671
y: 4140693.1229813518
theta: 1.534861357718238
kappa: -0.059924881581369258
s: 3.0761640542933586
x: 586343.76553587569
y: 4140692.6453840178
theta: 1.5636182480941849
kappa: -0.059347031331503874
s: 2.5982583195601867
dkappa: 0
ddkappa: 0
}
v: 2.9032668598924234
a: -3.01629552944893
v: 2.6082376892047003
a: -1.9033598918922539
relative_time: 0.80000000000000016
}
trajectory_point {
path_point {
x: 586343.78622408607
y: 4140693.2642675806
theta: 1.5262884380033852
kappa: -0.059956674821754319
s: 3.2175495890395664
x: 586343.76755760168
y: 4140692.7664914555
theta: 1.5564882048410404
kappa: -0.059844661668705959
s: 2.7194235927416495
dkappa: 0
ddkappa: 0
}
v: 2.7520460090964027
a: -3.0293457680979654
v: 2.5157715764169777
a: -1.876341073823355
relative_time: 0.8500000000000002
}
trajectory_point {
path_point {
x: 586343.79123862879
y: 4140693.3979895795
theta: 1.5181753711784363
kappa: -0.05998676590482168
s: 3.3513655769364465
x: 586343.77209807874
y: 4140692.8875716254
theta: 1.5491442072541122
kappa: -0.05987190799672315
s: 2.8405888659231122
dkappa: 0
ddkappa: 0
}
v: 2.6006376887560263
a: -3.0240716663429956
v: 2.4233054636292546
a: -1.849322255754456
relative_time: 0.90000000000000024
}
trajectory_point {
path_point {
x: 586343.79596999579
y: 4140693.5241601779
theta: 1.5105222138178442
kappa: -0.060015157717567096
s: 3.4776248565444874
x: 586343.77614242164
y: 4140692.9954214613
theta: 1.5426011812624609
kappa: -0.059896177140189563
s: 2.9485145062564824
dkappa: 0
ddkappa: 0
}
v: 2.4499165126235223
a: -3.0021373549028927
v: 2.3350412446419706
a: -1.8213096304181973
relative_time: 0.95000000000000029
}
trajectory_point {
path_point {
x: 586343.801806346
y: 4140693.6427425011
theta: 1.5033963334183187
kappa: -0.059906892302501222
s: 3.5963819169483884
x: 586343.78018676443
y: 4140693.1032712976
theta: 1.5360573236482196
kappa: -0.059920446283655976
s: 3.0564401465898525
dkappa: 0
ddkappa: 0
}
v: 2.3006738879151745
a: -2.9652069644965304
v: 2.2467770256546866
a: -1.7932970050819383
relative_time: 1.0000000000000002
}
trajectory_point {
path_point {
x: 586343.81226847484
y: 4140693.7535967217
theta: 1.4969674641941557
kappa: -0.059319495987640726
s: 3.7077287374302661
x: 586343.78423110722
y: 4140693.2111211335
theta: 1.5295131947547742
kappa: -0.059944715427122389
s: 3.1643657869232227
dkappa: 0
ddkappa: 0
}
v: 2.1536180153113254
a: -2.9149446258427805
v: 2.1585128066674026
a: -1.7652843797456794
relative_time: 1.0500000000000003
}
trajectory_point {
path_point {
x: 586343.82204611273
y: 4140693.8571982412
theta: 1.4909577366345843
kappa: -0.058770530419786512
s: 3.8117906271428561
x: 586343.78780377179
y: 4140693.3063928019
theta: 1.5237325083074553
kappa: -0.059966154141085304
s: 3.2597044186954429
dkappa: 0
ddkappa: 0
}
v: 2.0093738889563717
a: -2.853014469660514
v: 2.0745994162597348
a: -1.7362788558815732
relative_time: 1.1000000000000003
}
trajectory_point {
path_point {
x: 586343.83115377452
y: 4140693.9537008526
theta: 1.4853589151523277
kappa: -0.058259180665771307
s: 3.908722064782713
x: 586343.79137643636
y: 4140693.40166447
theta: 1.5179524338188752
kappa: -0.059987592855048219
s: 3.3550430504676627
dkappa: 0
ddkappa: 0
}
v: 1.8684832964587677
a: -2.7810806266686039
v: 1.9906860258520664
a: -1.7072733320174667
relative_time: 1.1500000000000004
}
trajectory_point {
path_point {
x: 586343.83960832492
y: 4140694.0432832511
theta: 1.480161133394164
kappa: -0.057784499859411226
s: 3.9987025382634176
x: 586343.79494910093
y: 4140693.4969361383
theta: 1.5121733573207803
kappa: -0.060009031569011134
s: 3.450381682239883
dkappa: 0
ddkappa: 0
}
v: 1.7314048188910238
a: -2.7008072275859236
v: 1.9067726354443983
a: -1.6782678081533604
relative_time: 1.2000000000000004
}
trajectory_point {
path_point {
x: 586343.8474285875
y: 4140694.1261448879
theta: 1.4753531685252357
kappa: -0.057345431148792779
s: 4.081932384388776
x: 586343.79807537969
y: 4140693.5803041109
theta: 1.5071174680812749
kappa: -0.060027791628047264
s: 3.5338082517423191
dkappa: 0
ddkappa: 0
}
v: 1.5985138307897073
a: -2.6138584031313434
v: 1.8273588869791735
a: -1.6482701952037377
relative_time: 1.2500000000000004
}
trajectory_point {
path_point {
x: 586343.8546349539
y: 4140694.2025018269
theta: 1.4709227122169637
kappa: -0.056940829643559912
s: 4.1586286285260252
x: 586343.80376568146
y: 4140693.6635031519
theta: 1.5021924895465939
kappa: -0.059796885397186687
s: 3.6172348212447556
dkappa: 0
ddkappa: 0
}
v: 1.47010250015544
a: -2.5218982840237363
v: 1.7479451385139488
a: -1.6182725822541151
relative_time: 1.3000000000000005
}
trajectory_point {
path_point {
x: 586343.86124899285
y: 4140694.2725826064
theta: 1.4668566379662811
kappa: -0.05656948436220105
s: 4.2290208242790355
x: 586343.81160442811
y: 4140693.7465606416
theta: 1.4973755676006557
kappa: -0.059356778896838436
s: 3.7006613907471917
dkappa: 0
ddkappa: 0
}
v: 1.3463797884529023
a: -2.4265910009819747
v: 1.6685313900487242
a: -1.5882749693044924
relative_time: 1.3500000000000005
}
trajectory_point {
path_point {
x: 586343.86729305971
y: 4140694.3366240966
theta: 1.4631412646171003
kappa: -0.056230140179336148
s: 4.29334689316151
x: 586343.81838943309
y: 4140693.8184529357
theta: 1.4932054159732215
kappa: -0.058975834733357976
s: 3.772873150187241
dkappa: 0
ddkappa: 0
}
v: 1.2274714506108295
a: -2.3296006847249306
v: 1.5937659896328111
a: -1.557285982309081
relative_time: 1.4000000000000006
}
trajectory_point {
path_point {
x: 586343.87278990459
y: 4140694.3948673536
theta: 1.4597626161455373
kappa: -0.05592151977300365
s: 4.3518489642701939
x: 586343.82517443807
y: 4140693.8903452288
theta: 1.4890347155994688
kappa: -0.0585948905698775
s: 3.8450849096272908
dkappa: 0
ddkappa: 0
}
v: 1.113420035022016
a: -2.2325914659714767
v: 1.5190005892168981
a: -1.5262969953136694
relative_time: 1.4500000000000006
}
trajectory_point {
path_point {
x: 586343.8777622825
y: 4140694.4475534838
theta: 1.4567066779123909
kappa: -0.055642345571947638
s: 4.4047692139580681
x: 586343.83195944293
y: 4140693.9622375229
theta: 1.4848636114911828
kappa: -0.05821394640639705
s: 3.9172966690673396
dkappa: 0
ddkappa: 0
}
v: 1.0041848835433091
a: -2.137227475440485
v: 1.444235188800985
a: -1.4953080083182577
relative_time: 1.5000000000000007
}
trajectory_point {
path_point {
x: 586343.88223417709
y: 4140694.4949366124
theta: 1.4539586570951915
kappa: -0.0553912710087195
s: 4.4523628974934661
x: 586343.83775831433
y: 4140694.0236809812
theta: 1.4812985256108682
kappa: -0.057888368714588606
s: 3.9790131624901957
dkappa: 0
ddkappa: 0
}
v: 0.90067792603003227
a: -2.0033754094197018
v: 1.3742667486863611
a: -1.4633282729763315
relative_time: 1.5500000000000007
}
trajectory_point {
path_point {
x: 586343.8862354391
y: 4140694.5373330303
theta: 1.4515001436751958
kappa: -0.055166620116531409
s: 4.4949477110694609
x: 586343.843557186
y: 4140694.0851244405
theta: 1.4777333414220735
kappa: -0.057562791022780176
s: 4.0407296559130517
dkappa: 0
ddkappa: 0
}
v: 0.803812827733087
a: -1.8715942354940154
v: 1.304298308571737
a: -1.4313485376344051
relative_time: 1.6000000000000008
}
trajectory_point {
path_point {
x: 586343.89045542979
y: 4140694.5749912546
theta: 1.4493946050270228
kappa: -0.054929031771843904
s: 4.5328530562099854
x: 586343.84935605747
y: 4140694.1465678997
theta: 1.4741681495529975
kappa: -0.057237213330971745
s: 4.1024461493359068
dkappa: 0
ddkappa: 0
}
v: 0.71347987474169927
a: -1.7421307259042034
v: 1.2343298684571129
a: -1.3993688022924786
relative_time: 1.6500000000000008
}
trajectory_point {
path_point {
x: 586343.89533660631
y: 4140694.6081837537
theta: 1.4476747107604819
kappa: -0.05465325308869165
s: 4.5664025402781281
x: 586343.85423849709
y: 4140694.1983010657
theta: 1.4711664478072033
kappa: -0.056963088712103711
s: 4.1544092004388249
dkappa: 0
ddkappa: 0
}
v: 0.62955701453305579
a: -1.6152316528910429
v: 1.1693069196575248
a: -1.3663988601922392
relative_time: 1.7000000000000008
}
trajectory_point {
path_point {
x: 586343.89963019
y: 4140694.6373805613
theta: 1.4461617464886747
kappa: -0.054410672461824752
s: 4.5959133595455395
x: 586343.85912093672
y: 4140694.2500342317
theta: 1.4681648589521374
kappa: -0.056688964093235678
s: 4.2063722515417421
dkappa: 0
ddkappa: 0
}
v: 0.55190985597230435
a: -1.4911437886953114
v: 1.1042839708579366
a: -1.333428918092
relative_time: 1.7500000000000009
}
trajectory_point {
path_point {
x: 586343.903381308
y: 4140694.662888546
theta: 1.4448398568428247
kappa: -0.054198740290442853
s: 4.6216956822618265
x: 586343.86400337645
y: 4140694.3017673977
theta: 1.4651634370632496
kappa: -0.056414839474367658
s: 4.2583353026446593
dkappa: 0
ddkappa: 0
}
v: 0.48039166931255428
a: -1.3701139055577869
v: 1.0392610220583487
a: -1.3004589759917606
relative_time: 1.8000000000000009
}
trajectory_point {
path_point {
x: 586343.90663397452
y: 4140694.685007012
theta: 1.4436935653991492
kappa: -0.054014969815694779
s: 4.6440520317239473
x: 586343.86804117833
y: 4140694.344550983
theta: 1.4626814108552186
kappa: -0.056188137051113786
s: 4.3013090043622979
dkappa: 0
ddkappa: 0
}
v: 0.41484338619487582
a: -1.2523887757192464
v: 0.97933202615648707
a: -1.2664992900069163
relative_time: 1.850000000000001
}
trajectory_point {
path_point {
x: 586343.90943100268
y: 4140694.7040270888
theta: 1.4427078094716512
kappa: -0.0538569421918835
s: 4.6632766693456169
x: 586343.8720789802
y: 4140694.3873345684
theta: 1.46019956637771
kappa: -0.055961434627859914
s: 4.3442827060799365
dkappa: 0
ddkappa: 0
}
v: 0.35509359964830023
a: -1.1382151714204674
v: 0.91940303025462555
a: -1.2325396040220722
relative_time: 1.900000000000001
}
trajectory_point {
path_point {
x: 586343.911813913
y: 4140694.7202311223
theta: 1.4418679741945675
kappa: -0.053722311557670994
s: 4.6796549777266971
x: 586343.87611678219
y: 4140694.4301181543
theta: 1.4577179341811315
kappa: -0.055734732204606049
s: 4.3872564077975742
dkappa: 0
ddkappa: 0
}
v: 0.30095856408982
a: -1.0278398649022276
v: 0.85947403435276426
a: -1.1985799180372279
relative_time: 1.9500000000000011
}
trajectory_point {
path_point {
x: 586343.913822845
y: 4140694.7338920655
theta: 1.441159926041178
kappa: -0.053608810107283314
s: 4.6934628437226005
x: 586343.87938383187
y: 4140694.4647350339
theta: 1.4557101823836642
kappa: -0.055551303667304007
s: 4.4220271135332307
dkappa: 0
ddkappa: 0
}
v: 0.25224219532438896
a: -0.92150962840530459
v: 0.80478739447288417
a: -1.163630877890687
relative_time: 2.0000000000000009
}
trajectory_point {
path_point {
x: 586343.91549646656
y: 4140694.7452728632
theta: 1.4405700458997015
kappa: -0.053514253161715312
s: 4.7049660415136865
x: 586343.88265088166
y: 4140694.4993519136
theta: 1.4537026057161435
kappa: -0.055367875130001971
s: 4.4567978192688864
dkappa: 0
ddkappa: 0
}
v: 0.20873607054492171
a: -0.81947123417047552
v: 0.75010075459300418
a: -1.1286818377441459
relative_time: 2.0500000000000007
}
trajectory_point {
path_point {
x: 586343.9168718846
y: 4140694.7546258457
theta: 1.4400852618043112
kappa: -0.053436544239935782
s: 4.7144196156746583
x: 586343.88591793133
y: 4140694.5339687937
theta: 1.4516952203359386
kappa: -0.055184446592699936
s: 4.491568525004543
dkappa: 0
ddkappa: 0
}
v: 0.17021942833229387
a: -0.72197145443851785
v: 0.6954141147131242
a: -1.093732797597605
relative_time: 2.1000000000000005
}
trajectory_point {
path_point {
x: 586343.91798455513
y: 4140694.7621921189
theta: 1.4396930813998314
kappa: -0.053373680130092242
s: 4.7220672642439618
x: 586343.88849020551
y: 4140694.5612239968
theta: 1.4501148736303362
kappa: -0.055040026237607335
s: 4.5189448413783415
dkappa: 0
ddkappa: 0
}
v: 0.13645916865534258
a: -0.6292570614502091
v: 0.64611818563407508
a: -1.0577947255920652
relative_time: 2.1500000000000004
}
trajectory_point {
path_point {
x: 586343.91886819364
y: 4140694.7682009516
theta: 1.4393816242022075
kappa: -0.053323755960715938
s: 4.7281407217931841
x: 586343.89241492876
y: 4140694.588316048
theta: 1.4487041873948996
kappa: -0.054818323204752009
s: 4.54632115775214
dkappa: 0
ddkappa: 0
}
v: 0.10720985287086615
a: -0.54157482744632657
v: 0.59682225655502585
a: -1.0218566535865254
relative_time: 2.2
}
trajectory_point {
path_point {
x: 586343.91955468548
y: 4140694.772869166
theta: 1.43913965370317
kappa: -0.053284970271926718
s: 4.7328591424964532
x: 586343.89639795979
y: 4140694.6154010654
theta: 1.4473007224649828
kappa: -0.054593288314087489
s: 4.5736974741259386
dkappa: 0
ddkappa: 0
}
v: 0.082213703723623466
a: -0.459171524667648
v: 0.54752632747597674
a: -0.98591858158098578
relative_time: 2.25
}
trajectory_point {
path_point {
x: 586343.92007399548
y: 4140694.776400527
theta: 1.4389566093563877
kappa: -0.053255630086638035
s: 4.7364284831998305
x: 586343.89942604979
y: 4140694.6359923864
theta: 1.446233683234367
kappa: -0.054422206060777391
s: 4.5945102551072745
dkappa: 0
ddkappa: 0
}
v: 0.06120060534633498
a: -0.38229392535495044
v: 0.50376942485955511
a: -0.94899173849680285
relative_time: 2.3
}
trajectory_point {
path_point {
x: 586343.92045407882
y: 4140694.7789851329
theta: 1.4388226384735121
kappa: -0.0532341559817618
s: 4.7390408864907148
x: 586343.90245413978
y: 4140694.6565837087
theta: 1.445166596347337
kappa: -0.0542511238074673
s: 4.6153230360886095
dkappa: 0
ddkappa: 0
}
v: 0.043888103259682509
a: -0.31118880174901142
v: 0.46001252224313338
a: -0.91206489541261981
relative_time: 2.3499999999999996
}
trajectory_point {
path_point {
x: 586343.92072079121
y: 4140694.7807988045
theta: 1.4387286280515919
kappa: -0.053219087159413384
s: 4.7408740637672375
x: 586343.90548222978
y: 4140694.67717503
theta: 1.4440994642309863
kappa: -0.054080041554157195
s: 4.6361358170699454
dkappa: 0
ddkappa: 0
}
v: 0.029981404372308451
a: -0.24610292609060891
v: 0.41625561962671165
a: -0.87513805232843689
relative_time: 2.3999999999999995
}
trajectory_point {
path_point {
x: 586343.92089779861
y: 4140694.7820024733
theta: 1.4386662365480676
kappa: -0.053209086518116469
s: 4.7420906783076617
x: 586343.9076794975
y: 4140694.692116675
theta: 1.443325096061614
kappa: -0.053955899434410134
s: 4.651238159357729
dkappa: 0
ddkappa: 0
}
v: 0.01917337698081667
a: -0.18728307062051996
v: 0.37818602833636733
a: -0.83722264348792086
relative_time: 2.4499999999999993
}
trajectory_point {
path_point {
x: 586343.92100648838
y: 4140694.7827415746
theta: 1.4386279256156427
kappa: -0.053202945724008049
s: 4.7428377283397785
x: 586343.90987676533
y: 4140694.70705832
theta: 1.4425507062833736
kappa: -0.053831757314663067
s: 4.6663405016455135
dkappa: 0
ddkappa: 0
}
v: 0.011144550769771611
a: -0.13497600757952188
v: 0.340116437046023
a: -0.79930723464740494
relative_time: 2.4999999999999991
}
trajectory_point {
path_point {
x: 586343.92106587836
y: 4140694.7831454324
theta: 1.4386069918065003
kappa: -0.053199590282043345
s: 4.743245930110306
x: 586343.912074033
y: 4140694.7219999656
theta: 1.4417762958241704
kappa: -0.053707615194916
s: 4.6814428439332971
dkappa: 0
ddkappa: 0
}
v: 0.0055631168116999641
a: -0.089428509208392626
v: 0.30204684575567869
a: -0.76139182580688891
relative_time: 2.5499999999999989
}
trajectory_point {
path_point {
x: 586343.92109252827
y: 4140694.7833266542
theta: 1.4385975982533308
kappa: -0.053198084607200678
s: 4.74342910095429
x: 586343.91356783267
y: 4140694.7321579559
theta: 1.4412498060446686
kappa: -0.053623217897298431
s: 4.691710083443799
dkappa: 0
ddkappa: 0
}
v: 0.0020849275670882239
a: -0.050887347747909484
v: 0.26981282724046529
a: -0.72248800730601581
relative_time: 2.5999999999999988
}
trajectory_point {
path_point {
x: 586343.921100449
y: 4140694.7833805159
theta: 1.4385948063332135
kappa: -0.053197637095686479
s: 4.7434835423644977
x: 586343.9150616324
y: 4140694.7423159461
theta: 1.440723307427251
kappa: -0.053538820599680861
s: 4.7019773229543009
dkappa: 0
ddkappa: 0
}
v: 0.00035349688438546245
a: -0.019599295438849307
v: 0.23757880872525194
a: -0.6835841888051426
relative_time: 2.6499999999999986
}
trajectory_point {
path_point {
x: 586343.92110101366
y: 4140694.7833843557
theta: 1.4385946073193652
kappa: -0.053197605196140162
s: 4.7434874230608184
x: 586343.916555432
y: 4140694.7524739364
theta: 1.4401968002635936
kappa: -0.053454423302063285
s: 4.7122445624648028
dkappa: 0
ddkappa: 0
}
v: 0
a: 0.0041888754780097237
v: 0.2053447902100386
a: -0.6446803703042695
relative_time: 2.6999999999999984
}
trajectory_point {
path_point {
x: 586343.92110286711
y: 4140694.7833969593
theta: 1.438593954024955
kappa: -0.053197500480839072
s: 4.7435001620596609
x: 586343.91747635324
y: 4140694.7587362942
theta: 1.4398722067136591
kappa: -0.053402392728448496
s: 4.7185742717831332
dkappa: 0
ddkappa: 0
}
v: 0.00064327353830306855
a: 0.02023039276188987
v: 0.17909458892889671
a: -0.60478825541045922
relative_time: 2.7499999999999982
}
trajectory_point {
path_point {
x: 586343.92111183656
y: 4140694.7834579526
theta: 1.4385907924424579
kappa: -0.053196993716903444
s: 4.7435618117433505
x: 586343.91839727422
y: 4140694.7649986516
theta: 1.4395476100948021
kappa: -0.053350362154833714
s: 4.7249039811014635
dkappa: 0
ddkappa: 0
}
v: 0.0018898155116264803
a: 0.028278484172014728
v: 0.1528443876477549
a: -0.564896140516649
relative_time: 2.799999999999998
}
trajectory_point {
path_point {
x: 586343.92113084206
y: 4140694.7835871922
theta: 1.4385840933812786
kappa: -0.053195919937501279
s: 4.74369244092953
x: 586343.91931819543
y: 4140694.7712610094
theta: 1.4392230104753814
kappa: -0.053298331581218911
s: 4.7312336904197947
dkappa: 0
ddkappa: 0
}
v: 0.00333378532026285
a: 0.02808637746760656
v: 0.1265941863666131
a: -0.52500402562283877
relative_time: 2.8499999999999979
}
trajectory_point {
path_point {
x: 586343.9211598062
y: 4140694.7837841511
theta: 1.4385738841055831
kappa: -0.053194283513053289
s: 4.7438915179405541
x: 586343.91980006243
y: 4140694.7745377552
theta: 1.4390531642825981
kappa: -0.053271106861029073
s: 4.7345456770673069
dkappa: 0
ddkappa: 0
}
v: 0.00455700375246515
a: 0.019407300407886741
v: 0.10647603522782156
a: -0.48412369134050259
relative_time: 2.8999999999999977
}
trajectory_point {
path_point {
x: 586343.92119556456
y: 4140694.7840273115
theta: 1.4385612799733578
kappa: -0.053192263222437905
s: 4.74413729367289
x: 586343.92028192955
y: 4140694.7778145
theta: 1.4388833172968158
kappa: -0.053243882140839235
s: 4.7378576637148182
dkappa: 0
ddkappa: 0
}
v: 0.0051289529844498194
a: 0.0019944807520788643
v: 0.086357884089030168
a: -0.44324335705816642
relative_time: 2.9499999999999975
}
trajectory_point {
path_point {
x: 586343.92123177613
y: 4140694.7842735541
theta: 1.4385485160767022
kappa: -0.053190217324196036
s: 4.7443861846665154
x: 586343.92076379666
y: 4140694.7810912454
theta: 1.4387134695278283
kappa: -0.053216657420649391
s: 4.74116965036233
dkappa: 0
ddkappa: 0
}
v: 0.0046067765803919913
a: -0.024398853740594362
v: 0.0662397329502388
a: -0.4023630227758303
relative_time: 2.9999999999999973
}
trajectory_point {
path_point {
x: 586343.921261114
y: 4140694.7844730546
theta: 1.4385381750589268
kappa: -0.053188559784638594
s: 4.7445878304077276
x: 586343.92094366893
y: 4140694.7823143955
theta: 1.4386500681953773
kappa: -0.053206494919635715
s: 4.74240595572848
dkappa: 0
ddkappa: 0
}
v: 0.0034941568319866133
a: -0.020185980781846913
v: 0.052401857741157354
a: -0.3604945165777626
relative_time: 3.0499999999999972
}
trajectory_point {
path_point {
x: 586343.92128309538
y: 4140694.78462253
theta: 1.4385304270343773
kappa: -0.053187317870700537
s: 4.744738913774297
x: 586343.92112354131
y: 4140694.7835375462
theta: 1.4385866667556693
kappa: -0.053196332418622039
s: 4.74364226109463
dkappa: 0
ddkappa: 0
}
v: 0.0025803846872339093
a: -0.01644073672151887
v: 0.03856398253207613
a: -0.31862601037969485
relative_time: 3.099999999999997
}
trajectory_point {
path_point {
x: 586343.92129908339
y: 4140694.7847312503
theta: 1.4385247915650845
kappa: -0.053186414573791869
s: 4.7448488031424665
x: 586343.92130341369
y: 4140694.7847606968
theta: 1.4385232652092133
kappa: -0.05318616991760837
s: 4.7448785664607795
dkappa: 0
ddkappa: 0
}
v: 0.001842710632156921
a: -0.013137844321859488
v: 0.024726107322994906
a: -0.27675750418162715
relative_time: 3.1499999999999968
}
trajectory_point {
path_point {
x: 586343.92131028
y: 4140694.7848073887
theta: 1.4385208449253168
kappa: -0.053185781975712623
s: 4.7449257610093269
x: 586343.92132158531
y: 4140694.7848842661
theta: 1.4385168600090472
kappa: -0.053185143242445249
s: 4.7450034652442321
dkappa: 0
ddkappa: 0
}
v: 0.0012596490146660286
a: -0.01025202634511628
v: 0.017316730105013646
a: -0.23390085090762552
relative_time: 3.1999999999999966
}
trajectory_point {
path_point {
x: 586343.92131773592
y: 4140694.78485809
theta: 1.438518216861101
kappa: -0.053185360729202061
s: 4.744977007185911
x: 586343.92133975716
y: 4140694.7850078363
theta: 1.4385104548077974
kappa: -0.053184116567282148
s: 4.7451283640276847
dkappa: 0
ddkappa: 0
}
v: 0.0008109780445592356
a: -0.0077580055535367426
v: 0.0099073528870326725
a: -0.1910441976336239
relative_time: 3.2499999999999964
}
trajectory_point {
path_point {
x: 586343.92132235889
y: 4140694.7848895267
theta: 1.4385165873496601
kappa: -0.05318509953848774
s: 4.7450087819902889
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00047773979352217118
a: -0.0056305047093683884
v: 0.0024979756690516955
a: -0.14818754435962225
relative_time: 3.2999999999999963
}
trajectory_point {
path_point {
x: 586343.92132492363
y: 4140694.7849069661
theta: 1.4385156833587913
kappa: -0.053184954639834713
s: 4.745026409440662
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00024224019512808764
a: -0.0038442465748587187
v: 0.0016653171127009134
a: -0.10434275328208534
relative_time: 3.3499999999999961
}
trajectory_point {
path_point {
x: 586343.92132608045
y: 4140694.7849148335
theta: 1.4385152756061999
kappa: -0.053184889282094638
s: 4.7450343604484573
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 8.8049044837863223e-05
a: -0.0023739539122552417
v: 0.0008326585563504824
a: -0.060497962204548367
relative_time: 3.3999999999999959
}
trajectory_point {
path_point {
x: 586343.92132636486
y: 4140694.7849167679
theta: 1.4385151753188032
kappa: -0.053184873207254894
s: 4.7450363160114239
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 2.6020852139652106e-18
a: -0.0011943494838054583
v: 5.2041704279304213e-17
a: -0.016653171127011396
relative_time: 3.4499999999999957
}
trajectory_point {
path_point {
x: 586343.921326207
y: 4140694.7849156936
theta: 1.4385152309920142
kappa: -0.0531848821309878
s: 4.7450352304067236
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -3.5809420149367915e-05
a: -0.00028015605175687325
v: 0
a: -0.011102114084672807
relative_time: 3.4999999999999956
}
trajectory_point {
path_point {
x: 586343.92132593982
y: 4140694.784913877
theta: 1.438515325149011
kappa: -0.053184897223199655
s: 4.745033394384027
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -3.2017834486495166e-05
a: 0.00039390362164300891
v: 0
a: -0.0055510570423366011
relative_time: 3.5499999999999954
}
trajectory_point {
path_point {
x: 586343.92132580956
y: 4140694.7849129904
theta: 1.4385153711000018
kappa: -0.053184904588579975
s: 4.74503249835861
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -4.3368086899420177e-18
a: 0.00085310677414667663
v: 0
a: -3.95516952522712e-16
relative_time: 3.5999999999999952
}
trajectory_point {
path_point {
x: 586343.92132598371
y: 4140694.784914175
theta: 1.4385153097014842
kappa: -0.05318489474715056
s: 4.7450336956044437
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.0133188209109704e-05
a: 0.0011227306435066323
v: 0
a: 0
relative_time: 3.649999999999995
}
trajectory_point {
path_point {
x: 586343.92132656125
y: 4140694.7849181024
theta: 1.4385151061155033
kappa: -0.053184862114814657
s: 4.7450376654472937
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00010953469692747027
a: 0.0012280524674753712
v: 0
a: 0
relative_time: 3.6999999999999948
}
trajectory_point {
path_point {
x: 586343.92132758128
y: 4140694.7849250394
theta: 1.4385147465689121
kappa: -0.053184804483906112
s: 4.7450446764578107
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00017062135482933272
a: 0.001194349483805382
v: 0
a: 0
relative_time: 3.7499999999999947
}
trajectory_point {
path_point {
x: 586343.9213290324
y: 4140694.7849349058
theta: 1.4385142351126314
kappa: -0.0531847225037385
s: 4.7450546496446266
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00022707385247657322
a: 0.0010468989302491634
v: 0
a: 0
relative_time: 3.7999999999999945
}
trajectory_point {
path_point {
x: 586343.92133086151
y: 4140694.784947345
theta: 1.43851359038091
kappa: -0.053184619161154287
s: 4.7450672216474494
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00027383674231868695
a: 0.00081097804455921435
v: 0
a: 0
relative_time: 3.8499999999999943
}
trajectory_point {
path_point {
x: 586343.92133298365
y: 4140694.7849617754
theta: 1.4385128423505873
kappa: -0.053184499261073895
s: 4.7450818079301555
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.0003071184386928081
a: 0.00051186406448801985
v: 0
a: 0
relative_time: 3.8999999999999941
}
trajectory_point {
path_point {
x: 586343.92133529088
y: 4140694.7849774649
theta: 1.4385120291003537
kappa: -0.053184368907044949
s: 4.7450976659738862
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00032439121782367863
a: 0.00017483422778808225
v: 0
a: 0
relative_time: 3.949999999999994
}
trajectory_point {
path_point {
x: 586343.92133766133
y: 4140694.7849935843
theta: 1.4385111935700137
kappa: -0.05318423498179134
s: 4.7451139584701405
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.0003243912178236795
a: -0.00017483422778808572
v: 0
a: 0
relative_time: 3.9999999999999938
}
trajectory_point {
path_point {
x: 586343.92133996857
y: 4140694.7850092733
theta: 1.438510380319745
kappa: -0.0531841046277624
s: 4.74512981651387
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.0003071184386928081
a: -0.00051186406448803026
v: 0
a: 0
relative_time: 4.0499999999999936
}
trajectory_point {
path_point {
x: 586343.9213420907
y: 4140694.7850237042
theta: 1.4385096322893587
kappa: -0.053183984727682009
s: 4.7451444027965763
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00027383674231868781
a: -0.00081097804455921088
v: 0
a: 0
relative_time: 4.0999999999999934
}
trajectory_point {
path_point {
x: 586343.92134391982
y: 4140694.7850361424
theta: 1.438508987557559
kappa: -0.053183881385097782
s: 4.7451569747993991
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00022707385247657062
a: -0.0010468989302491634
v: 0
a: 0
relative_time: 4.1499999999999932
}
trajectory_point {
path_point {
x: 586343.92134537082
y: 4140694.7850460103
theta: 1.4385084761012004
kappa: -0.053183799404930183
s: 4.7451669479862151
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00017062135482933533
a: -0.0011943494838053924
v: 0
a: 0
relative_time: 4.1999999999999931
}
trajectory_point {
path_point {
x: 586343.92134639085
y: 4140694.7850529463
theta: 1.4385081165545464
kappa: -0.053183741774021638
s: 4.7451739589967321
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.000109534696927472
a: -0.0012280524674753886
v: 0
a: 0
relative_time: 4.2499999999999929
}
trajectory_point {
path_point {
x: 586343.92134696851
y: 4140694.7850568737
theta: 1.4385079129685268
kappa: -0.053183709141685742
s: 4.7451779288395821
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.01331882091071e-05
a: -0.0011227306435066704
v: 0
a: 0
relative_time: 4.2999999999999927
}
trajectory_point {
path_point {
x: 586343.92134714266
y: 4140694.7850580583
theta: 1.4385078515699969
kappa: -0.053183699300256314
s: 4.7451791260854161
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -6.0715321659188248e-18
a: -0.00085310677414671132
v: 0
a: 0
relative_time: 4.3499999999999925
}
trajectory_point {
path_point {
x: 586343.92134701228
y: 4140694.7850571717
theta: 1.4385078975209971
kappa: -0.05318370666563664
s: 4.7451782300599987
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -3.20178344864995e-05
a: -0.00039390362164306789
v: 0
a: 0
relative_time: 4.3999999999999924
}
trajectory_point {
path_point {
x: 586343.92134674522
y: 4140694.7850553556
theta: 1.4385079916780121
kappa: -0.0531837217578485
s: 4.7451763940373022
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -3.5809420149373987e-05
a: 0.0002801560517568108
v: 0
a: 0
relative_time: 4.4499999999999922
}
trajectory_point {
path_point {
x: 586343.92134658713
y: 4140694.7850542809
theta: 1.4385080473512335
kappa: -0.053183730681581394
s: 4.7451753084326018
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -7.8062556418956319e-18
a: 0.0011943494838053612
v: 0
a: 0
relative_time: 4.499999999999992
}
trajectory_point {
path_point {
x: 586343.92134678585
y: 4140694.7850556318
theta: 1.4385079773253671
kappa: -0.053183719457295962
s: 4.74517667390792
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.2152229983493646e-05
a: 0.00089829880018893775
v: 0
a: 0
relative_time: 4.5499999999999918
}
trajectory_point {
path_point {
x: 586343.9213473124
y: 4140694.7850592127
theta: 1.4385077917218512
kappa: -0.053183689707334392
s: 4.7451802930994047
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 9.0467413187375549e-05
a: 0.0006405001066817831
v: 0
a: 0
relative_time: 4.5999999999999917
}
trajectory_point {
path_point {
x: 586343.921348073
y: 4140694.7850643853
theta: 1.4385075236160612
kappa: -0.053183646733272964
s: 4.7451855210509377
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00011680302322626789
a: 0.00041874836765039855
v: 0
a: 0
relative_time: 4.6499999999999915
}
trajectory_point {
path_point {
x: 586343.92134898691
y: 4140694.7850706
theta: 1.4385072014618703
kappa: -0.053183595095917843
s: 4.74519180292379
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00013290628193311595
a: 0.00023083854746105525
v: 0
a: 0
relative_time: 4.6999999999999913
}
trajectory_point {
path_point {
x: 586343.921349986
y: 4140694.7850773931
theta: 1.4385068493743518
kappa: -0.053183538660618944
s: 4.7451986684840275
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00014041415935917852
a: 7.4565610480025e-05
v: 0
a: 0
relative_time: 4.7499999999999911
}
trajectory_point {
path_point {
x: 586343.92135101277
y: 4140694.7850843756
theta: 1.4385064874124831
kappa: -0.053183480642583665
s: 4.7452057265899263
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00014085337377402814
a: -5.2275478926420938e-05
v: 0
a: 0
relative_time: 4.7999999999999909
}
trajectory_point {
path_point {
x: 586343.92135202151
y: 4140694.7850912348
theta: 1.4385061318618475
kappa: -0.053183423652190726
s: 4.74521265967938
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00013564039166555071
a: -0.00015188975639201076
v: 0
a: 0
relative_time: 4.8499999999999908
}
trajectory_point {
path_point {
x: 586343.92135297577
y: 4140694.7850977238
theta: 1.4385057955173375
kappa: -0.053183369740303972
s: 4.7452192182573132
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00012608142773994589
a: -0.00022648225755047342
v: 0
a: 0
relative_time: 4.8999999999999906
}
trajectory_point {
path_point {
x: 586343.9213538483
y: 4140694.7851036568
theta: 1.4385054879658579
kappa: -0.053183320443586139
s: 4.7452252153830905
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 0.00011337244492172682
a: -0.00027825801803553723
v: 0
a: 0
relative_time: 4.94999999999999
}
trajectory_point {
path_point {
x: 586343.92135462025
y: 4140694.7851089062
theta: 1.4385052158690277
kappa: -0.053183276829812685
s: 4.7452305211579278
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 9.8599154353720041e-05
a: -0.00030942207348093071
v: 0
a: 0
relative_time: 4.99999999999999
}
trajectory_point {
path_point {
x: 586343.92135528021
y: 4140694.7851133943
theta: 1.4385049832458834
kappa: -0.053183239543185566
s: 4.7452350572123034
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 8.2737015397066154e-05
a: -0.00032217945952038259
v: 0
a: 0
relative_time: 5.04999999999999
}
trajectory_point {
path_point {
x: 586343.9213558234
y: 4140694.7851170884
theta: 1.4385047917555815
kappa: -0.053183208849647036
s: 4.7452387911933718
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 6.6651235631218824e-05
a: -0.00031873521178762076
v: 0
a: 0
relative_time: 5.09999999999999
}
trajectory_point {
path_point {
x: 586343.92135625123
y: 4140694.7851199973
theta: 1.4385046409801017
kappa: -0.053183184682193477
s: 4.745241731252368
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.1096770853945644e-05
a: -0.0003012943659163748
v: 0
a: 0
relative_time: 5.14999999999999
}
trajectory_point {
path_point {
x: 586343.92135656974
y: 4140694.7851221636
theta: 1.4385045287069493
kappa: -0.053183166686189137
s: 4.7452439205320243
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 3.6718325081327467e-05
a: -0.00027206195754037217
v: 0
a: 0
relative_time: 5.1999999999999895
}
trajectory_point {
path_point {
x: 586343.92135678953
y: 4140694.7851236584
theta: 1.4385044512118583
kappa: -0.05318315426467999
s: 4.7452454316539807
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 2.40503505477589e-05
a: -0.00023324302229334247
v: 0
a: 0
relative_time: 5.2499999999999893
}
trajectory_point {
path_point {
x: 586343.92135692481
y: 4140694.785124578
theta: 1.4385044035414947
kappa: -0.0531831466237075
s: 4.7452463612061919
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 1.3517047705948256e-05
a: -0.00018704259580901335
v: 0
a: 0
relative_time: 5.2999999999999892
}
trajectory_point {
path_point {
x: 586343.92135699221
y: 4140694.7851250358
theta: 1.4385043797961585
kappa: -0.053183142817622438
s: 4.7452468242303416
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.4323652269173008e-06
a: -0.00013566571372111312
v: 0
a: 0
relative_time: 5.349999999999989
}
trajectory_point {
path_point {
x: 586343.92135701026
y: 4140694.7851251592
theta: 1.438504373412488
kappa: -0.053183141794398647
s: 4.7452469487092532
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 7.8435250915748211e-19
a: -8.13174116633716e-05
v: 0
a: 0
relative_time: 5.3999999999999888
}
trajectory_point {
path_point {
x: 586343.92135699885
y: 4140694.7851250814
theta: 1.4385043774461619
kappa: -0.053183142440946886
s: 4.7452468700542987
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -2.6866028671514522e-06
a: -2.6202725269516879e-05
v: 0
a: 0
relative_time: 5.4499999999999886
}
trajectory_point {
path_point {
x: 586343.92135697789
y: 4140694.7851249385
theta: 1.4385043848546015
kappa: -0.053183143628428582
s: 4.7452467255928124
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -2.64425004857751e-06
a: 2.7473309826723602e-05
v: 0
a: 0
relative_time: 5.4999999999999885
}
trajectory_point {
path_point {
x: 586343.92135696672
y: 4140694.785124863
theta: 1.438504388779676
kappa: -0.053183144257569696
s: 4.745246649055499
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: -1.3628760121321692e-18
a: 7.7505657991621324e-05
v: 0
a: 0
relative_time: 5.5499999999999883
}
trajectory_point {
path_point {
x: 586343.9213569836
y: 4140694.7851249776
theta: 1.4385043828304027
kappa: -0.053183143303974431
s: 4.7452467650638459
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 5.0088370411665887e-06
a: 0.00012168928359144581
v: 0
a: 0
relative_time: 5.5999999999999881
}
trajectory_point {
path_point {
x: 586343.92135704448
y: 4140694.785125392
theta: 1.4385043613656519
kappa: -0.053183139863439088
s: 4.7452471836175363
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 1.2034699055829769e-05
a: 0.00015781915099247049
v: 0
a: 0
relative_time: 5.6499999999999879
}
trajectory_point {
path_point {
x: 586343.92135716241
y: 4140694.7851261939
theta: 1.4385043197768483
kappa: -0.053183133197265871
s: 4.745247994581856
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 2.0619772243204178e-05
a: 0.00018369022456096468
v: 0
a: 0
relative_time: 5.6999999999999877
}
trajectory_point {
path_point {
x: 586343.92135734693
y: 4140694.7851274479
theta: 1.4385042547706759
kappa: -0.053183122777576662
s: 4.745249262175105
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 3.019599102082197e-05
a: 0.00019709746866320224
v: 0
a: 0
relative_time: 5.7499999999999876
}
trajectory_point {
path_point {
x: 586343.92135760258
y: 4140694.7851291872
theta: 1.4385041646517782
kappa: -0.053183108332626822
s: 4.7452510194560125
x: 586343.92135792889
y: 4140694.785131406
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 4.008503802452524e-05
a: 0.00019583584766545443
v: 0
a: 0
relative_time: 5.7999999999999874
}
trajectory_point {
path_point {
x: 586343.92135792889
y: 4140694.785131406
theta: 1.438504049605464
kappa: -0.053183089892118986
s: 4.7452532628111435
theta: 1.4385040496054642
kappa: -0.053183089892119034
s: 4.7452532628111372
dkappa: 0
ddkappa: 0
}
v: 4.9498344108471663e-05
a: 0.00017770032593399055
v: 0
a: 0
relative_time: 5.8499999999999872
}
trajectory_point {
path_point {
x: 586343.92135831935
y: 4140694.7851340612
theta: 1.4385039119804075
kappa: -0.053183067832516875
s: 4.7452559464423105
x: 586343.92136116361
y: 4140694.7851534025
theta: 1.4385029094233188
kappa: -0.053182907134961252
s: 4.7452754958868892
dkappa: 0
ddkappa: 0
}
v: 5.75370883451332e-05
a: 0.00014048586783508427
v: 0.00014822050501524814
a: 0.000988136700101654
relative_time: 5.899999999999987
}
trajectory_point {
path_point {
x: 586343.92135876033
y: 4140694.7851370592
theta: 1.4385037565713543
kappa: -0.053183042922359113
s: 4.7452589768539859
x: 586343.92136439844
y: 4140694.7851753989
theta: 1.4385017692411393
kappa: -0.053182724377803463
s: 4.7452977289626421
dkappa: 0
ddkappa: 0
}
v: 6.319219802529324e-05
a: 8.1987437735004873e-05
v: 0.00029644101003054366
a: 0.0019762734002036243
relative_time: 5.9499999999999869
}
trajectory_point {
path_point {
x: 586343.9213592303
y: 4140694.7851402555
theta: 1.4385035909018218
kappa: -0.053183016367572944
s: 4.7452622073407129
x: 586343.92136763316
y: 4140694.7851973958
theta: 1.4385006290589253
kappa: -0.053182541620645687
s: 4.7453199620383941
dkappa: 0
ddkappa: 0
}
v: 6.5344348658051882e-05
a: 2.6020852139652106e-17
v: 0.00044466151504583915
a: 0.0029644101003055943
relative_time: 5.9999999999999867
}
decision {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册