-
Notifications
You must be signed in to change notification settings - Fork 0
/
interpolate.cc
2203 lines (1840 loc) · 63.7 KB
/
interpolate.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*
* @Author: your name
* @Date: 2023-08-12 20:17:37
* @LastEditTime: 2023-08-12 20:17:37
* @LastEditors: LAPTOP-GLMMQRJB
* @Description: In User Settings Edit
* @FilePath: \UR_RTDE_Dynamics\interpolate.cc
*/
#include "interpolate.h"
namespace rocos
{
double PULSE::pos( double time )
{
double ret = 0;
int n = time / _cycle; // 第几个周期
double m = time - n * _cycle; // 减去正周期整数倍的剩余时间
switch ( _type )
{
case VEL: // 速度方波,则位移三角波
if ( m > _cycle * _ratio ) // 剩余时间超过半个周期
{
ret = n * ( _amp * ( _cycle * ( 2.0 * _ratio - 1.0 ) ) ) + _amp * ( _cycle * _ratio ) -
_amp * ( m - _cycle * _ratio );
}
else
{
ret = n * ( _amp * ( _cycle * ( _ratio * 2.0 - 1.0 ) ) ) + _amp * m;
}
return ret;
break;
case ACC: // 加速度方波,速度是三角波,位移是递增
double v0 = 0;
for ( int i = 0; i < n; i++ )
{
double t = _cycle * _ratio;
ret = ret + v0 * t + 0.5 * _amp * t * t;
v0 = v0 + _amp * t;
t = _cycle - _cycle * _ratio;
ret = ret + v0 * t - 0.5 * _amp * t * t;
v0 = v0 - _amp * t;
}
if ( m > _cycle * _ratio )
{
ret = ret + v0 * _cycle * _ratio + 0.5 * _amp * ( _cycle * _ratio ) * ( _cycle * _ratio );
v0 = v0 + _amp * ( _cycle * _ratio );
ret = ret + v0 * ( _cycle * ( m - _cycle * _ratio ) ) -
0.5 * _amp * ( _cycle * ( m - _cycle * _ratio ) ) * ( _cycle * ( m - _cycle * _ratio ) );
v0 = v0 - _amp * ( _cycle * ( m - _cycle * _ratio ) );
}
else
{
ret = ret + v0 * ( _cycle * m ) + 0.5 * _amp * ( m ) * ( m );
}
return ret;
break;
}
return ret;
}
double PULSE::vel( double time )
{
double ret = 0;
int n = time / _cycle; // 第几个周期
double m = time - n * _cycle; // 减去正周期整数倍的剩余时间
switch ( _type )
{
case VEL:
if ( m > _cycle * _ratio )
{
return -_amp;
}
else
{
return _amp;
}
break;
case ACC:
PULSE temp( VEL, _cycle, _ratio, _amp );
return temp.pos( time );
return ret;
break;
}
return ret;
}
// 通用插补
#pragma region universel
bool R_INTERP::planProfile( )
{
if ( _pTarget == _pStart )
{
printf( "please input valid target!\n" );
}
if ( _v_limit == 0.0 || _a_limit == 0.0 )
{
printf( "please input valid velocity or acceleration limit!\n" );
}
//TODO 改动二:new->std::make_shared
switch ( _pType )
{
case trapezoid:
if ( _trapezoid == nullptr )
{
_trapezoid = std::make_shared< Trapezoid >( );
}
_pCurProfileType = _trapezoid;
_trapezoid->planTrapezoidProfile( _tStart, _pStart, _pTarget, _vStart, _vTarget, _v_limit, _a_limit );
break;
case doubleS:
if ( _doubleS == nullptr )
{
_doubleS = std::make_shared< DoubleS >( );
}
_pCurProfileType = _doubleS;
_doubleS->planDoubleSProfile( _tStart, _pStart, _pTarget, _vStart, _vTarget, _v_limit, _a_limit,
_j_limit );
break;
case polynomial_3rd_T:
if ( _tTerminal == 0 || _tTerminal <= _tStart )
{
printf( "please input valid terminal time!\n" );
}
if ( _polynomial == nullptr )
{
_polynomial = std::make_shared< Polynomial >( );
}
_pCurProfileType = _polynomial;
_polynomial->plan3rdProfileT( _tStart, _tTerminal, _pStart, _pTarget, _vStart, _vTarget );
break;
case polynomial_5th_T:
if ( _tTerminal == 0 || _tTerminal <= _tStart )
{
printf( "please input valid terminal time!\n" );
}
if ( _polynomial == nullptr )
{
_polynomial = std::make_shared< Polynomial >( );
}
_pCurProfileType = _polynomial;
_polynomial->plan5thProfileT( _tStart, _tTerminal, _pStart, _pTarget, _vStart, _vTarget, _aStart,
_aTarget );
break;
case harmonic_T:
if ( _tTerminal == 0 || _tTerminal <= _tStart )
{
printf( "please input valid terminal time!\n" );
}
if ( _trigonometric == nullptr )
{
_trigonometric = std::make_shared< Trigonometric >( );
}
_pCurProfileType = _trigonometric;
_trigonometric->planHarmonicProfileT( _pStart, _pTarget, _tStart, _tTerminal );
break;
case cycloidal_T:
if ( _tTerminal == 0 || _tTerminal <= _tStart )
{
printf( "please input valid terminal time!\n" );
}
if ( _trigonometric == nullptr )
{
_trigonometric = std::make_shared< Trigonometric >( );
}
_pCurProfileType = _trigonometric;
_trigonometric->planCycloidalProfileT( _pStart, _pTarget, _tStart, _tTerminal );
break;
case elliptic_T:
if ( _tTerminal == 0 || _tTerminal <= _tStart )
{
printf( "please input valid terminal time!\n" );
}
if ( _trigonometric == nullptr )
{
_trigonometric = std::make_shared< Trigonometric >( );
}
_pCurProfileType = _trigonometric;
_trigonometric->planEllipticProfileT( _pStart, _pTarget, _tStart, _tTerminal, 1.5 );
break;
case unDefine:
_pType = doubleS;
planProfile( );
if ( !_pCurProfileType->isValidMovement( ) )
{
_pType = trapezoid;
planProfile( );
}
break;
}
return isValidMovement( );
}
bool R_INTERP::planDoubleSPorfile( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit, double j_limit )
{
setStartTime( t0 );
setStart( p0, v0 );
setTarget( pf, vf );
setLimit( v_limit, a_limit, j_limit );
if ( _doubleS == nullptr )
{
//TODO 改动三:new ->std::make_shared
_doubleS = std::make_shared< DoubleS >( );
}
_pCurProfileType = _doubleS;
_doubleS->planDoubleSProfile( t0, p0, pf, v0, vf, v_limit, a_limit, j_limit );
return _doubleS->isValidMovement( );
}
bool R_INTERP::planTrapezoidProfile( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit )
{
setStart( p0, v0 );
setTarget( pf, vf );
setStartTime( t0 );
setLimit( v_limit, a_limit );
if ( _trapezoid == nullptr )
{ //TODO 改动四:new ->std::make_shared
_trapezoid = std::make_shared< Trapezoid >( );
}
_pCurProfileType = _trapezoid;
_trapezoid->planTrapezoidProfile( t0, p0, pf, v0, vf, v_limit, a_limit );
return _trapezoid->isValidMovement( );
}
bool R_INTERP::plan3rdProfileT( double t0, double tf, double p0,
double pf, double v0, double vf )
{
setStartTime( t0 );
setTargetTime( tf );
setStart( p0, v0 );
setTarget( pf, vf );
if ( _polynomial == nullptr )
{ //TODO 改动5:new ->std::make_shared
_polynomial = std::make_shared< Polynomial >( );
}
_pCurProfileType = _polynomial;
_polynomial->plan3rdProfileT( t0, tf, p0, pf, v0, vf );
return _polynomial->isValidMovement( );
}
bool R_INTERP::plan5thProfileT( double t0, double tf, double p0,
double pf, double v0, double vf, double a0, double af )
{
setStartTime( t0 );
setTargetTime( tf );
setStart( p0, v0, a0 );
setTarget( pf, vf, af );
if ( _polynomial == nullptr )
{ //TODO 改动6:new ->std::make_shared
_polynomial = std::make_shared< Polynomial >( );
}
_pCurProfileType = _polynomial;
_polynomial->plan5thProfileT( t0, tf, p0, pf, v0, vf, a0, af );
return _polynomial->isValidMovement( );
}
#pragma endregion universel
// T型波
#pragma region TRAPEZOID
void Trapezoid::planProfile( double t0, double p0, double pf, double v0, double vf, double v_limit, double a_limit,
double j_limit )
{
planTrapezoidProfile( t0, p0, pf, v0, vf, v_limit, a_limit );
}
void Trapezoid::planTrapezoidProfile( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit )
{
_plannedProfile = false;
_direction = sign( pf - p0 );
if ( _direction == 0 )
{
// std::cerr<<("target and start points are the same!\n");
return;
}
double p0_z = _direction * p0;
double pf_z = _direction * pf;
double v0_z = _direction * v0;
double vf_z = _direction * vf;
double vmax = fabs( v_limit );
double amax = fabs( a_limit );
double vmin = -vmax;
double amin = -amax;
double v_limit_z = ( _direction + 1.0 ) / 2.0 * vmax + ( _direction - 1.0 ) / 2.0 * vmin;
double a_limit_z = ( _direction + 1.0 ) / 2.0 * amax + ( _direction - 1.0 ) / 2.0 * amin;
trapezoid_check_T( t0, p0_z, pf_z, v0_z, vf_z, v_limit_z, a_limit_z );
}
void Trapezoid::trapezoid_check_T( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit )
{
// the 'trapezoid' profile trajectory looks like :
//
// v | _________
// | / \
// |/ \
// | \
// | |
// 0-1--------2---3--> t
// let Ta Tv Td be the acceleration cursing and deceleration time interval
// so, pf - p0 = v0*Ta +0.5*_a[1]*Ta*Ta + _v[1]*Tv + vf*Td - 0.5*_a[3]*Td*Td
// Ta = (_v[1] - _v[0])/_a[1]; // here, _a[1],acceleration, bigger than zero
// Td = (_v[3] - _v[2])/_a[3]; // here, _a[3],deceleration, samller than zero,
// Tv = ((pf-p0) - (_v[0]*Ta + 0.5*_a[1]*Ta*Ta) - (_v[3]*Td - 0.5*_a[3]*Td*Td))/_v[1];
_t[ 0 ] = t0; // start time
_x[ 0 ] = p0;
_x[ 3 ] = pf;
_v[ 0 ] = v0;
_v[ 3 ] = vf;
_a[ 0 ] = 0;
_a[ 2 ] = 0;
double amax = a_limit; // a_limit: acceleration in phase #1;
_a[ 1 ] = a_limit; // plan the trajectory with the limited acceleration
double amin = -a_limit; //amin: acceleration in phase #3, be deceleration.
_a[ 3 ] = amin; // by default, deceleration equals to minus acceleration
// it is necessary to check whether the trajectory is feasible or not by
if ( a_limit * ( pf - p0 ) < fabs( v0 * v0 - vf * vf ) / 2.0 )
{
std::cerr << ( "trapezoid trajectory is not feasible\n" );
_plannedProfile = false;
return;
}
else
{
double Ta, Tv, Td;
if ( ( pf - p0 ) * a_limit > v_limit * v_limit - ( v0 * v0 + vf * vf ) / 2.0 )
{
// Case 1: _v[1] = v_limit
_v[ 1 ] = v_limit;
}
else
{
// Case 2: _v[1] < v_limit
_v[ 1 ] = sqrt( ( pf - p0 ) * a_limit + ( v0 * v0 + vf * vf ) / 2.0 );
}
_v[ 2 ] = _v[ 1 ];
Ta = ( _v[ 1 ] - _v[ 0 ] ) / _a[ 1 ];
Td = ( _v[ 3 ] - _v[ 2 ] ) / _a[ 3 ];
Tv = ( ( pf - p0 ) - ( _v[ 0 ] * Ta + 0.5 * _a[ 1 ] * Ta * Ta ) - ( _v[ 3 ] * Td - 0.5 * _a[ 3 ] * Td * Td ) ) / _v[ 1 ];
_t[ 1 ] = _t[ 0 ] + Ta;
_t[ 2 ] = _t[ 1 ] + Tv;
_t[ 3 ] = _t[ 2 ] + Td;
_x[ 1 ] = _x[ 0 ] + _v[ 0 ] * Ta / 2.0 + _v[ 1 ] * ( Ta - Ta / 2.0 );
_x[ 2 ] = _x[ 0 ] + _v[ 0 ] * Ta / 2.0 + _v[ 1 ] * ( Tv - Ta / 2.0 );
}
_plannedProfile = true;
}
double Trapezoid::scaleToDuration( double newDuration )
{
if ( newDuration < ( _t[ 3 ] - _t[ 0 ] ) )
{
// std::cerr<<("New duration must be longer!\n");
return _t[ 3 ] - _t[ 0 ];
}
double p0 = _x[ 0 ];
double pf = _x[ 3 ];
double v0 = _v[ 0 ];
double vf = _v[ 3 ];
double h = pf - p0;
double T = _t[ 3 ] - _t[ 0 ];
double Ta = _t[ 1 ] - _t[ 0 ];
double Tv = _t[ 2 ] - _t[ 1 ];
double Td = _t[ 3 ] - _t[ 2 ];
Ta = Ta * newDuration / T;
Tv = Tv * newDuration / T;
Td = Td * newDuration / T;
// 3 equations to get new _v[1] _a[1] and _a[3]
// Ta = (_v[1] - v0)/_a[1];
// Tv = ((pf-p0) - (_v[0]*Ta + 0.5*_a[1]*Ta*Ta) - (_v[3]*Td - 0.5*_a[3]*Td*Td))/_v[1];
// Td = (_v[3] - _v[1])/_a[3];
_a[ 1 ] = -( 1.0 * ( 2.0 * p0 - 2.0 * pf + 2.0 * Ta * v0 + Td * v0 + 2.0 * Tv * v0 + Td * vf ) ) /
( Ta * ( Ta + Td + 2.0 * Tv ) );
_a[ 3 ] = ( 2.0 * p0 - 2.0 * pf + Ta * v0 + Ta * vf + 2.0 * Td * vf + 2.0 * Tv * vf ) / ( Td * ( Ta + Td + 2.0 * Tv ) );
_v[ 1 ] = -( 1.0 * ( 2.0 * p0 - 2.0 * pf + Ta * v0 + Td * vf ) ) / ( Ta + Td + 2.0 * Tv );
_v[ 2 ] = _v[ 1 ];
Ta = ( _v[ 1 ] - _v[ 0 ] ) / _a[ 1 ];
Td = ( _v[ 3 ] - _v[ 2 ] ) / _a[ 3 ];
Tv = ( ( pf - p0 ) - ( _v[ 0 ] * Ta + 0.5 * _a[ 1 ] * Ta * Ta ) - ( _v[ 3 ] * Td - 0.5 * _a[ 3 ] * Td * Td ) ) / _v[ 1 ];
_t[ 1 ] = _t[ 0 ] + Ta;
_t[ 2 ] = _t[ 1 ] + Tv;
_t[ 3 ] = _t[ 2 ] + Td;
_x[ 1 ] = _x[ 0 ] + _v[ 0 ] * Ta / 2.0 + _v[ 1 ] * ( Ta - Ta / 2.0 );
_x[ 2 ] = _x[ 0 ] + _v[ 0 ] * Ta / 2.0 + _v[ 1 ] * ( Tv - Ta / 2.0 );
return getDuration( );
}
bool Trapezoid::isValidMovement( ) const
{
return _plannedProfile;
}
double Trapezoid::getDuration( ) const
{
return ( _t[ 3 ] - _t[ 0 ] );
}
double Trapezoid::pos( double t ) const
{
double p;
double dt = ( t - _t[ 0 ] );
double ta = _t[ 1 ] - _t[ 0 ];
double tv = _t[ 2 ] - _t[ 1 ];
double td = _t[ 3 ] - _t[ 2 ];
double T = _t[ 3 ] - _t[ 0 ];
if ( dt < 0 )
{
p = _x[ 0 ];
}
if ( dt < ta && dt >= 0 )
{
p = _x[ 0 ] + _v[ 0 ] * dt + ( _v[ 1 ] - _v[ 0 ] ) / 2.0 / ta * dt * dt;
}
if ( ta <= dt && dt < ta + tv )
{
p = _x[ 0 ] + _v[ 0 ] * ta / 2.0 + _v[ 1 ] * ( dt - ta / 2.0 );
}
if ( ta + tv <= dt && dt < T )
{
p = _x[ 3 ] - _v[ 3 ] * ( T - dt ) - ( _v[ 2 ] - _v[ 3 ] ) / 2.0 / td * ( T - dt ) * ( T - dt );
}
if ( dt >= T )
{
dt = T;
p = _x[ 3 ] - _v[ 3 ] * ( T - dt ) - ( _v[ 2 ] - _v[ 3 ] ) / 2.0 / td * ( T - dt ) * ( T - dt );
}
p = p * _direction;
return p;
}
double Trapezoid::vel( double t ) const
{
double v;
double dt = ( t - _t[ 0 ] );
double ta = _t[ 1 ] - _t[ 0 ];
double tv = _t[ 2 ] - _t[ 1 ];
double td = _t[ 3 ] - _t[ 2 ];
double T = _t[ 3 ] - _t[ 0 ];
if ( dt < 0 )
{
v = _v[ 0 ];
}
if ( dt < ta && dt >= 0 )
{
v = _v[ 0 ] + ( _v[ 1 ] - _v[ 0 ] ) / ta * dt;
}
if ( ta <= dt && dt < ta + tv )
{
v = _v[ 1 ];
}
if ( ta + tv <= dt && dt < T )
{
v = _v[ 3 ] + ( _v[ 2 ] - _v[ 3 ] ) / td * ( T - dt );
}
if ( dt >= T )
{
dt = T;
v = _v[ 3 ] + ( _v[ 2 ] - _v[ 3 ] ) / td * ( T - dt );
}
v = v * _direction;
return v;
}
double Trapezoid::acc( double t ) const
{
double a;
double dt = ( t - _t[ 0 ] );
double ta = _t[ 1 ] - _t[ 0 ];
double tv = _t[ 2 ] - _t[ 1 ];
double td = _t[ 3 ] - _t[ 2 ];
double T = _t[ 3 ] - _t[ 0 ];
if ( dt < 0 )
{
a = 0.0;
}
if ( dt < ta && dt >= 0 )
{
a = _a[ 1 ];
}
if ( ta <= dt && dt < ta + tv )
{
a = _a[ 2 ];
}
if ( ta + tv <= dt && dt < T )
{
a = _a[ 3 ];
}
if ( dt >= T )
{
a = 0.0;
}
a = a * _direction;
return a;
}
double Trapezoid::jerk( double t ) const
{
return 0;
}
double Trapezoid::max_vel( ) const
{
double v = 0;
for ( int i = 0; i < 4; i++ )
{
v = fmax( fabs( v ), fabs( _v[ i ] ) );
}
for ( int i = 0; i < 4; i++ )
{
if ( v == fabs( _v[ i ] ) )
{
v = _v[ i ] * _direction;
}
}
return v;
}
double Trapezoid::max_acc( ) const
{
double a = 0;
for ( int i = 0; i < 4; i++ )
{
a = fmax( fabs( a ), fabs( _a[ i ] ) );
}
for ( int i = 0; i < 4; i++ )
{
if ( fabs( a ) == fabs( _a[ i ] ) )
{
a = _a[ i ] * _direction;
}
}
return a;
}
#pragma endregion TRAPEZOID
// S型波
#pragma region DOUBLES
void DoubleS::planProfile( double t0, double p0, double pf, double v0, double vf, double v_limit, double a_limit,
double j_limit )
{
planDoubleSProfile( t0, p0, pf, v0, vf, v_limit, a_limit, j_limit );
}
void DoubleS::planDoubleSProfile( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit, double j_limit )
{
_plannedProfile = false;
_direction = sign( pf - p0 );
if ( _direction == 0 )
{
_t[ 0 ] = t0;
_t[ 7 ] = t0;
std::cerr << ( "target and start points are the same!\n" );
return;
}
double p0_z = _direction * p0;
double pf_z = _direction * pf;
double v0_z = _direction * v0;
double vf_z = _direction * vf;
double vmax = fabs( v_limit );
double amax = fabs( a_limit );
double jmax = fabs( j_limit );
double vmin = -vmax;
double amin = -amax;
double jmin = -jmax;
double v_limit_z = ( _direction + 1.0 ) / 2.0 * vmax + ( _direction - 1.0 ) / 2.0 * vmin;
double a_limit_z = ( _direction + 1.0 ) / 2.0 * amax + ( _direction - 1.0 ) / 2.0 * amin;
double j_limit_z = ( _direction + 1.0 ) / 2.0 * jmax + ( _direction - 1.0 ) / 2.0 * jmin;
doubleS_check_T( t0, p0_z, pf_z, v0_z, vf_z, v_limit_z, a_limit_z, j_limit );
}
void DoubleS::doubleS_check_T( double t0, double p0, double pf,
double v0, double vf, double v_limit, double a_limit, double j_limit )
{
// the 'doubleS' has acceleration phase, cursing phase and deceleration phase
// in acceleration phase and deceleration phase, the acceleration has three phases:
// acc acceleration phase, acc cursing phase and acc deceleration phase
// a | _________
// | / \
// |/ \
// 0--1- -----2--3-------4--5------6--7-----------> t
// \ /
// \ /
// ---------
// the time interval between 0~1 is: Ta_acc
// the time interval between 1~2 is: Tv_acc
// the time interval between 2~3 is: Td_acc
// the time interval between 0~3 is: Ta
// the time interval between 3~4 is: Tv
// the time interval between 4~5 is: Ta_dec
// the time interval between 5~6 is: Tv_dec
// the time interval between 6~7 is: Td_dec
// the time interval between 4~7 is: Td
// by default, Td_acc = Ta_acc, and Ta_dec = Td_dec
_t[ 0 ] = t0; // start time
_x[ 0 ] = p0;
_x[ 7 ] = pf;
_v[ 0 ] = v0;
_v[ 7 ] = vf;
_a[ 0 ] = 0;
_a[ 4 ] = 0;
_a[ 3 ] = 0;
_a[ 7 ] = 0;
_j[ 0 ] = 0;
_j[ 2 ] = 0;
_j[ 4 ] = 0;
_j[ 6 ] = 0;
double r = 1; // scale factor for re-planning doubleS profile
// It is necessary to check if it is possible to perform the trajectory
// with a double jerk impulse(one positive and one negative) only.
// For this purpose, let us define
double Tjx = fmin( sqrt( fabs( vf - v0 ) / j_limit ), a_limit / j_limit );
if ( Tjx == a_limit / j_limit )
{
if ( pf - p0 <= 0.5 * ( v0 + vf ) * ( Tjx + fabs( vf - v0 ) / a_limit ) )
{
_plannedProfile = false;
std::cerr << ( "The two points are two close! DoubleS trajectory is not feasible!\n" );
return;
}
}
else
{
if ( pf - p0 <= Tjx * ( vf + v0 ) )
{
_plannedProfile = false;
std::cerr << ( "The two points are two close! DoubleS trajectory is not feasible!\n" );
return;
}
}
// In this case, by defining the maximum value of the velocity during
// the motion as vmax = max(v(t)), there are two possibilities:
// Case 1: vmax = v_limit
// Case 2: vmax < v_limit
// In both Case 1 and Case 2, it is possible that the limited
// acceleration(positive or negative) is not reached. This may happen if
// the displacement is small, if the limited allowed acceleration a_limit is high.
// Let us define:
// Ta: acceleration period;
// Tv: constant velocity period;
// Td: deceleration period;
// T: total duration of the trajectory (=Ta+Tv+Td);
// Ta_acc: acceleration increasing time-interval during acceleration peroid;
// Tv_acc: acceleration keep constant time-interval during acceleration period;
// Td_acc: acceleration decreasing time-interval during acceleration peroid;
// Ta_dec: deceleration increasing time-interval during deceleration peroid;
// Tv_dec: deceleration keep constant time-interval during decelration peroid;
// Td_dec: deceleration decreasing time-interval during deceleration period.
double Ta, Tv, Td, T, Ta_acc, Tv_acc, Td_acc, Ta_dec, Tv_dec, Td_dec;
double jmax_a, jmin_a, jmax_d, jmin_d, amax_a, amin_d, vmax;
// Case 1: vmax = v_limit
if ( ( v_limit - v0 ) * j_limit < a_limit * a_limit ) // acceleration phase
{
// a_limit is not reached
Ta_acc = sqrt( ( v_limit - v0 ) / j_limit );
Ta = 2 * Ta_acc;
}
else
{
// a_limit is reached
Ta_acc = a_limit / j_limit;
Ta = Ta_acc + ( v_limit - v0 ) / a_limit;
}
if ( ( v_limit - vf ) * j_limit < a_limit * a_limit ) // deceleration phase
{
// a_limit is not reached
Ta_dec = sqrt( ( v_limit - vf ) / j_limit );
Td = 2 * Ta_dec;
}
else
{
// a_limit is reached
Ta_dec = a_limit / j_limit;
Td = Ta_dec + ( v_limit - vf ) / a_limit;
}
// Finally, it is possible to determine the time duration of the
// constant velocity segments as
Tv = ( pf - p0 ) / v_limit - Ta / 2.0 * ( 1.0 + v0 / v_limit ) - Td / 2.0 * ( 1.0 + vf / v_limit );
if ( Tv <= 0 )
{
// Case 2: vmax < v_max
// In this case, the constant velocity segment is not present(Tv=0),
// and the duration of the acceleration and deceleration segments
// can be easily computed if the limited accelerations are reached
// in both segments. In this case
double temp = 0;
while ( 1 )
{
Ta_acc = a_limit / j_limit;
Ta_dec = a_limit / j_limit;
temp = ( a_limit * a_limit * a_limit * a_limit ) / ( j_limit * j_limit ) + 2.0 * ( v0 * v0 + vf * vf ) + a_limit * ( 4.0 * ( pf - p0 ) - 2.0 * a_limit / j_limit * ( v0 + vf ) );
Ta = ( ( a_limit * a_limit ) / j_limit - 2.0 * v0 + sqrt( temp ) ) / 2.0 / a_limit;
Td = ( ( a_limit * a_limit ) / j_limit - 2.0 * vf + sqrt( temp ) ) / 2.0 / a_limit;
Tv = 0;
// if Ta<2*Ta_acc or Td<2*Ta_dec, then the limited acceleration is
// not reached in at least one of the two segments, and therefore it
// is not possible to use above eq. In this case(indeed rather
// unusual), the determination of parameters is quite difficult, and
// it may be more convenient to find an approximated solution that,
// although not optimal, results acceptable from a computational
// point of view. A possible way to determine this solution is to
// progressively decrease the value of a_limit (e.g. by assuming
// a_limit=r*a_limit, with 0<r<1) and compute the duration of the
// segments by means of above eq. until the condition Ta>2*Ta_acc and
// Td>2*Ta_dec are both true.
if ( Ta < 0 || Td < 0 )
{
// During this recursive computation,it may happen that Ta
// or Td became negative. In this case, only one of the
// acceleration or deceleration phase is necessary,
// depending on the values of the initial and final
// velocities. If Ta<0 (note that in this case necessarily
// v0>v1), the acceleration phase is not present. Then, Ta
// is set to 0 and the duration of the deceleration segment
// can be computed according to
if ( Ta < 0 )
{
Td = 2 * ( pf - p0 ) / ( vf + v0 );
Ta_dec = ( j_limit * ( pf - p0 ) - sqrt( j_limit * ( j_limit * ( pf - p0 ) * ( pf - p0 ) +
( vf + v0 ) * ( vf + v0 ) * ( vf - v0 ) ) ) ) /
( j_limit * ( vf + v0 ) );
Ta = 0.0;
Ta_acc = 0.0;
break;
}
// In the dual case, i.e. when Td<0 (this case is possible
// when v1>v0), the deceleration phase is not necessary
// (Td=0) and the duration of the acceleration period must
// be computed as
if ( Td < 0 )
{
Ta = 2 * ( pf - p0 ) / ( vf + v0 );
Ta_acc = ( j_limit * ( pf - p0 ) - sqrt( j_limit * ( j_limit * ( pf - p0 ) * ( pf - p0 ) -
( vf + v0 ) * ( vf + v0 ) * ( vf - v0 ) ) ) ) /
( j_limit * ( vf + v0 ) );
Td = 0;
Ta_dec = 0;
break;
}
}
else
{
if ( ( Ta < 2 * Ta_acc ) || ( Td < 2 * Ta_dec ) )
{
r = r - 0.01;
a_limit = r * a_limit;
//std::cerr<<("DoubleS re-planning: Ta<2*Tj1 or Td<2*Tj2\n");
}
else
{
break;
}
}
}
}
amax_a = j_limit * Ta_acc;
amin_d = -j_limit * Ta_dec;
vmax = v0 + ( Ta - Ta_acc ) * amax_a;
jmax_a = j_limit;
jmin_a = -j_limit;
jmax_d = -j_limit;
jmin_d = j_limit;
Td_acc = Ta_acc;
Tv_acc = Ta - 2.0 * Ta_acc;
Td_dec = Ta_dec;
Tv_dec = Td - 2.0 * Ta_dec;
T = Ta + Tv + Td;
_j[ 1 ] = jmax_a;
_j[ 3 ] = jmin_a;
_j[ 5 ] = jmax_d;
_j[ 7 ] = jmin_d;
_t[ 0 ] = t0;
_t[ 1 ] = _t[ 0 ] + Ta_acc;
_t[ 2 ] = _t[ 1 ] + Tv_acc;
_t[ 3 ] = _t[ 2 ] + Td_acc;
_t[ 4 ] = _t[ 3 ] + Tv;
_t[ 5 ] = _t[ 4 ] + Ta_dec;
_t[ 6 ] = _t[ 5 ] + Tv_dec;
_t[ 7 ] = _t[ 6 ] + Td_dec;
_a[ 1 ] = amax_a;
_a[ 2 ] = amax_a;
_a[ 5 ] = amin_d;
_a[ 6 ] = amin_d;
_v[ 3 ] = vmax;
_v[ 4 ] = vmax;
_v[ 1 ] = vel( _t[ 1 ] );
_v[ 2 ] = vel( _t[ 2 ] );
_v[ 5 ] = vel( _t[ 5 ] );
_v[ 6 ] = vel( _t[ 6 ] );
_plannedProfile = true;
}
double DoubleS::scaleToDuration( double newDuration )
{
if ( newDuration <= ( _t[ 7 ] - _t[ 0 ] ) )
{
std::cerr << ( "New duration must be longer!\n" );
return _t[ 7 ] - _t[ 0 ];
}
double t0 = _t[ 0 ];
double p0 = _x[ 0 ];
double pf = _x[ 7 ];
double v0 = _v[ 0 ];
double vf = _v[ 7 ];
double j_limit = _j[ 1 ];
double Ta = _t[ 3 ] - _t[ 0 ];
double Tv = _t[ 4 ] - _t[ 3 ];
double Td = _t[ 7 ] - _t[ 4 ];
double T = _t[ 7 ] - _t[ 0 ];
Ta = Ta * newDuration / T;
Tv = Tv * newDuration / T;
Td = Td * newDuration / T;
// decrease the cursing velocity
double vmax = -( p0 - pf + ( Ta * v0 ) / 2 + ( Td * vf ) / 2 ) / ( Ta / 2 + Td / 2 + Tv );
double amax_a = _a[ 1 ];
// decrease jmax_a jmin_a jmax_d jmin_d and re-plan time interval
double Ta_acc, Ta_dec, jmax_a, jmax_d, amin_d;
if ( ( vmax - v0 ) * j_limit < amax_a * amax_a )
{
Ta_acc = 0.5 * Ta;
jmax_a = ( vmax - v0 ) / ( Ta_acc * Ta_acc );
}
else
{
Ta_acc = Ta - ( vmax - v0 ) / amax_a;
jmax_a = amax_a / Ta_acc;
}
if ( ( vmax - vf ) * j_limit < amax_a * amax_a )
{
Ta_dec = 0.5 * Td;
jmax_d = -( vmax - vf ) / ( Ta_dec * Ta_dec );
}
else
{
Ta_dec = Td - ( vmax - vf ) / amax_a;
jmax_d = -amax_a / Ta_dec;
}
amax_a = jmax_a * Ta_acc;
amin_d = jmax_d * Ta_dec;
vmax = v0 + ( Ta - Ta_acc ) * amax_a;
double tempTv = ( pf - p0 ) / vmax - Ta / 2.0 * ( 1.0 + v0 / vmax ) - Td / 2.0 * ( 1.0 + vf / vmax );
if ( tempTv < 0 || fabs( tempTv - Tv ) > 1e-4 )
{
std::cerr << ( "Re-plan to scale duration failed!\n" );
return getDuration( );
}
T = Ta + Tv + Td;
_j[ 1 ] = jmax_a;
_j[ 3 ] = -jmax_a;
_j[ 5 ] = jmax_d;
_j[ 7 ] = -jmax_d;
double Td_acc = Ta_acc;
double Tv_acc = Ta - 2.0 * Ta_acc;
double Td_dec = Ta_dec;
double Tv_dec = Td - 2.0 * Ta_dec;
_t[ 0 ] = t0;
_t[ 1 ] = _t[ 0 ] + Ta_acc;
_t[ 2 ] = _t[ 1 ] + Tv_acc;
_t[ 3 ] = _t[ 2 ] + Td_acc;
_t[ 4 ] = _t[ 3 ] + Tv;
_t[ 5 ] = _t[ 4 ] + Ta_dec;
_t[ 6 ] = _t[ 5 ] + Tv_dec;
_t[ 7 ] = _t[ 6 ] + Td_dec;
_a[ 1 ] = amax_a;
_a[ 2 ] = amax_a;
_a[ 5 ] = amin_d;
_a[ 6 ] = amin_d;