-
Notifications
You must be signed in to change notification settings - Fork 138
/
b_traj_node.cpp
1594 lines (1290 loc) · 52.5 KB
/
b_traj_node.cpp
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
#include <iostream>
#include <fstream>
#include <math.h>
#include <random>
#include <eigen3/Eigen/Dense>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/search/kdtree.h>
#include <ros/ros.h>
#include <ros/console.h>
#include <sensor_msgs/PointCloud2.h>
#include <nav_msgs/Odometry.h>
#include <nav_msgs/Path.h>
#include <geometry_msgs/PoseStamped.h>
#include <visualization_msgs/MarkerArray.h>
#include <visualization_msgs/Marker.h>
#include <tf/tf.h>
#include <tf/transform_datatypes.h>
#include <tf/transform_broadcaster.h>
#include "trajectory_generator.h"
#include "bezier_base.h"
#include "data_type.h"
#include "utils.h"
#include "a_star.h"
#include "backward.hpp"
#include "quadrotor_msgs/PositionCommand.h"
#include "quadrotor_msgs/PolynomialTrajectory.h"
using namespace std;
using namespace Eigen;
using namespace sdf_tools;
namespace backward {
backward::SignalHandling sh;
}
// simulation param from launch file
double _vis_traj_width;
double _resolution, _inv_resolution;
double _cloud_margin, _cube_margin, _check_horizon, _stop_horizon;
double _x_size, _y_size, _z_size, _x_local_size, _y_local_size, _z_local_size;
double _MAX_Vel, _MAX_Acc;
bool _is_use_fm, _is_proj_cube, _is_limit_vel, _is_limit_acc;
int _step_length, _max_inflate_iter, _traj_order;
double _minimize_order;
// useful global variables
nav_msgs::Odometry _odom;
bool _has_odom = false;
bool _has_map = false;
bool _has_target= false;
bool _has_traj = false;
bool _is_emerg = false;
bool _is_init = true;
Vector3d _start_pt, _start_vel, _start_acc, _end_pt;
double _init_x, _init_y, _init_z;
Vector3d _map_origin;
double _pt_max_x, _pt_min_x, _pt_max_y, _pt_min_y, _pt_max_z, _pt_min_z;
int _max_x_id, _max_y_id, _max_z_id, _max_local_x_id, _max_local_y_id, _max_local_z_id;
int _traj_id = 1;
COLLISION_CELL _free_cell(0.0);
COLLISION_CELL _obst_cell(1.0);
// ros related
ros::Subscriber _map_sub, _pts_sub, _odom_sub;
ros::Publisher _fm_path_vis_pub, _local_map_vis_pub, _inf_map_vis_pub, _corridor_vis_pub, _traj_vis_pub, _grid_path_vis_pub, _nodes_vis_pub, _traj_pub, _checkTraj_vis_pub, _stopTraj_vis_pub;
// trajectory related
int _seg_num;
VectorXd _seg_time;
MatrixXd _bezier_coeff;
// bezier basis constant
MatrixXd _MQM, _FM;
VectorXd _C, _Cv, _Ca, _Cj;
// useful object
quadrotor_msgs::PolynomialTrajectory _traj;
ros::Time _start_time = ros::TIME_MAX;
TrajectoryGenerator _trajectoryGenerator;
CollisionMapGrid * collision_map = new CollisionMapGrid();
CollisionMapGrid * collision_map_local = new CollisionMapGrid();
gridPathFinder * path_finder = new gridPathFinder();
void rcvWaypointsCallback(const nav_msgs::Path & wp);
void rcvPointCloudCallBack(const sensor_msgs::PointCloud2 & pointcloud_map);
void rcvOdometryCallbck(const nav_msgs::Odometry odom);
void trajPlanning();
bool checkExecTraj();
bool checkCoordObs(Vector3d checkPt);
vector<pcl::PointXYZ> pointInflate( pcl::PointXYZ pt);
void visPath(vector<Vector3d> path);
void visCorridor(vector<Cube> corridor);
void visGridPath( vector<Vector3d> grid_path);
void visExpNode( vector<GridNodePtr> nodes);
void visBezierTrajectory(MatrixXd polyCoeff, VectorXd time);
pair<Cube, bool> inflateCube(Cube cube, Cube lstcube);
Cube generateCube( Vector3d pt) ;
bool isContains(Cube cube1, Cube cube2);
void corridorSimplify(vector<Cube> & cubicList);
vector<Cube> corridorGeneration(vector<Vector3d> path_coord, vector<double> time);
vector<Cube> corridorGeneration(vector<Vector3d> path_coord);
void sortPath(vector<Vector3d> & path_coord, vector<double> & time);
void timeAllocation(vector<Cube> & corridor, vector<double> time);
void timeAllocation(vector<Cube> & corridor);
VectorXd getStateFromBezier(const MatrixXd & polyCoeff, double t_now, int seg_now );
Vector3d getPosFromBezier(const MatrixXd & polyCoeff, double t_now, int seg_now );
quadrotor_msgs::PolynomialTrajectory getBezierTraj();
void rcvOdometryCallbck(const nav_msgs::Odometry odom)
{
if (odom.header.frame_id != "uav")
return ;
_odom = odom;
_has_odom = true;
_start_pt(0) = _odom.pose.pose.position.x;
_start_pt(1) = _odom.pose.pose.position.y;
_start_pt(2) = _odom.pose.pose.position.z;
_start_vel(0) = _odom.twist.twist.linear.x;
_start_vel(1) = _odom.twist.twist.linear.y;
_start_vel(2) = _odom.twist.twist.linear.z;
_start_acc(0) = _odom.twist.twist.angular.x;
_start_acc(1) = _odom.twist.twist.angular.y;
_start_acc(2) = _odom.twist.twist.angular.z;
if( std::isnan(_odom.pose.pose.position.x) || std::isnan(_odom.pose.pose.position.y) || std::isnan(_odom.pose.pose.position.z))
return;
static tf::TransformBroadcaster br;
tf::Transform transform;
transform.setOrigin( tf::Vector3(_odom.pose.pose.position.x, _odom.pose.pose.position.y, _odom.pose.pose.position.z) );
transform.setRotation(tf::Quaternion(0, 0, 0, 1.0));
br.sendTransform(tf::StampedTransform(transform, ros::Time::now(), "world", "quadrotor"));
}
void rcvWaypointsCallback(const nav_msgs::Path & wp)
{
if(wp.poses[0].pose.position.z < 0.0)
return;
_is_init = false;
_end_pt << wp.poses[0].pose.position.x,
wp.poses[0].pose.position.y,
wp.poses[0].pose.position.z;
_has_target = true;
_is_emerg = true;
ROS_INFO("[Fast Marching Node] receive the way-points");
trajPlanning();
}
Vector3d _local_origin;
void rcvPointCloudCallBack(const sensor_msgs::PointCloud2 & pointcloud_map)
{
pcl::PointCloud<pcl::PointXYZ> cloud;
pcl::fromROSMsg(pointcloud_map, cloud);
if((int)cloud.points.size() == 0)
return;
delete collision_map_local;
ros::Time time_1 = ros::Time::now();
collision_map->RestMap();
double local_c_x = (int)((_start_pt(0) - _x_local_size/2.0) * _inv_resolution + 0.5) * _resolution;
double local_c_y = (int)((_start_pt(1) - _y_local_size/2.0) * _inv_resolution + 0.5) * _resolution;
double local_c_z = (int)((_start_pt(2) - _z_local_size/2.0) * _inv_resolution + 0.5) * _resolution;
_local_origin << local_c_x, local_c_y, local_c_z;
Translation3d origin_local_translation( _local_origin(0), _local_origin(1), _local_origin(2));
Quaterniond origin_local_rotation(1.0, 0.0, 0.0, 0.0);
Affine3d origin_local_transform = origin_local_translation * origin_local_rotation;
double _buffer_size = 2 * _MAX_Vel;
double _x_buffer_size = _x_local_size + _buffer_size;
double _y_buffer_size = _y_local_size + _buffer_size;
double _z_buffer_size = _z_local_size + _buffer_size;
collision_map_local = new CollisionMapGrid(origin_local_transform, "world", _resolution, _x_buffer_size, _y_buffer_size, _z_buffer_size, _free_cell);
vector<pcl::PointXYZ> inflatePts(20);
pcl::PointCloud<pcl::PointXYZ> cloud_inflation;
pcl::PointCloud<pcl::PointXYZ> cloud_local;
for (int idx = 0; idx < (int)cloud.points.size(); idx++)
{
auto mk = cloud.points[idx];
pcl::PointXYZ pt(mk.x, mk.y, mk.z);
if( fabs(pt.x - _start_pt(0)) > _x_local_size / 2.0 || fabs(pt.y - _start_pt(1)) > _y_local_size / 2.0 || fabs(pt.z - _start_pt(2)) > _z_local_size / 2.0 )
continue;
cloud_local.push_back(pt);
inflatePts = pointInflate(pt);
for(int i = 0; i < (int)inflatePts.size(); i++)
{
pcl::PointXYZ inf_pt = inflatePts[i];
Vector3d addPt(inf_pt.x, inf_pt.y, inf_pt.z);
collision_map_local->Set3d(addPt, _obst_cell);
collision_map->Set3d(addPt, _obst_cell);
cloud_inflation.push_back(inf_pt);
}
}
_has_map = true;
cloud_inflation.width = cloud_inflation.points.size();
cloud_inflation.height = 1;
cloud_inflation.is_dense = true;
cloud_inflation.header.frame_id = "world";
cloud_local.width = cloud_local.points.size();
cloud_local.height = 1;
cloud_local.is_dense = true;
cloud_local.header.frame_id = "world";
sensor_msgs::PointCloud2 inflateMap, localMap;
pcl::toROSMsg(cloud_inflation, inflateMap);
pcl::toROSMsg(cloud_local, localMap);
_inf_map_vis_pub.publish(inflateMap);
_local_map_vis_pub.publish(localMap);
ros::Time time_3 = ros::Time::now();
//ROS_WARN("Time in receving the map is %f", (time_3 - time_1).toSec());
if( checkExecTraj() == true )
trajPlanning();
}
vector<pcl::PointXYZ> pointInflate( pcl::PointXYZ pt)
{
int num = int(_cloud_margin * _inv_resolution);
int num_z = max(1, num / 2);
vector<pcl::PointXYZ> infPts(20);
pcl::PointXYZ pt_inf;
for(int x = -num ; x <= num; x ++ )
for(int y = -num ; y <= num; y ++ )
for(int z = -num_z ; z <= num_z; z ++ )
{
pt_inf.x = pt.x + x * _resolution;
pt_inf.y = pt.y + y * _resolution;
pt_inf.z = pt.z + z * _resolution;
infPts.push_back( pt_inf );
}
return infPts;
}
bool checkExecTraj()
{
if( _has_traj == false )
return false;
Vector3d traj_pt;
visualization_msgs::Marker _check_traj_vis, _stop_traj_vis;
geometry_msgs::Point pt;
_stop_traj_vis.header.stamp = _check_traj_vis.header.stamp = ros::Time::now();
_stop_traj_vis.header.frame_id = _check_traj_vis.header.frame_id = "world";
_check_traj_vis.ns = "trajectory/check_trajectory";
_stop_traj_vis.ns = "trajectory/stop_trajectory";
_stop_traj_vis.id = _check_traj_vis.id = 0;
_stop_traj_vis.type = _check_traj_vis.type = visualization_msgs::Marker::SPHERE_LIST;
_stop_traj_vis.action = _check_traj_vis.action = visualization_msgs::Marker::ADD;
_stop_traj_vis.scale.x = 2.0 * _vis_traj_width;
_stop_traj_vis.scale.y = 2.0 * _vis_traj_width;
_stop_traj_vis.scale.z = 2.0 * _vis_traj_width;
_check_traj_vis.scale.x = 1.5 * _vis_traj_width;
_check_traj_vis.scale.y = 1.5 * _vis_traj_width;
_check_traj_vis.scale.z = 1.5 * _vis_traj_width;
_check_traj_vis.pose.orientation.x = 0.0;
_check_traj_vis.pose.orientation.y = 0.0;
_check_traj_vis.pose.orientation.z = 0.0;
_check_traj_vis.pose.orientation.w = 1.0;
_stop_traj_vis.pose = _check_traj_vis.pose;
_stop_traj_vis.color.r = 0.0;
_stop_traj_vis.color.g = 1.0;
_stop_traj_vis.color.b = 0.0;
_stop_traj_vis.color.a = 1.0;
_check_traj_vis.color.r = 0.0;
_check_traj_vis.color.g = 0.0;
_check_traj_vis.color.b = 1.0;
_check_traj_vis.color.a = 1.0;
double t_s = max(0.0, (_odom.header.stamp - _start_time).toSec());
int idx;
for (idx = 0; idx < _seg_num; ++idx)
{
if( t_s > _seg_time(idx) && idx + 1 < _seg_num)
t_s -= _seg_time(idx);
else
break;
}
double duration = 0.0;
double t_ss;
for(int i = idx; i < _seg_num; i++ )
{
t_ss = (i == idx) ? t_s : 0.0;
for(double t = t_ss; t < _seg_time(i); t += 0.01)
{
double t_d = duration + t - t_ss;
if( t_d > _check_horizon ) break;
traj_pt = getPosFromBezier( _bezier_coeff, t/_seg_time(i), i );
pt.x = traj_pt(0) = _seg_time(i) * traj_pt(0);
pt.y = traj_pt(1) = _seg_time(i) * traj_pt(1);
pt.z = traj_pt(2) = _seg_time(i) * traj_pt(2);
_check_traj_vis.points.push_back(pt);
if( t_d <= _stop_horizon )
_stop_traj_vis.points.push_back(pt);
if( checkCoordObs(traj_pt))
{
ROS_WARN("predicted collision time is %f ahead", t_d);
if( t_d <= _stop_horizon )
{
ROS_ERROR("emergency occurs in time is %f ahead", t_d);
_is_emerg = true;
}
_checkTraj_vis_pub.publish(_check_traj_vis);
_stopTraj_vis_pub.publish(_stop_traj_vis);
return true;
}
}
duration += _seg_time(i) - t_ss;
}
_checkTraj_vis_pub.publish(_check_traj_vis);
_stopTraj_vis_pub.publish(_stop_traj_vis);
return false;
}
bool checkCoordObs(Vector3d checkPt)
{
if(collision_map->Get(checkPt(0), checkPt(1), checkPt(2)).first.occupancy > 0.0 )
return true;
return false;
}
pair<Cube, bool> inflateCube(Cube cube, Cube lstcube)
{
Cube cubeMax = cube;
// Inflate sequence: left, right, front, back, below, above
MatrixXi vertex_idx(8, 3);
for (int i = 0; i < 8; i++)
{
double coord_x = max(min(cube.vertex(i, 0), _pt_max_x), _pt_min_x);
double coord_y = max(min(cube.vertex(i, 1), _pt_max_y), _pt_min_y);
double coord_z = max(min(cube.vertex(i, 2), _pt_max_z), _pt_min_z);
Vector3d coord(coord_x, coord_y, coord_z);
Vector3i pt_idx = collision_map->LocationToGridIndex(coord);
if( collision_map->Get( (int64_t)pt_idx(0), (int64_t)pt_idx(1), (int64_t)pt_idx(2) ).first.occupancy > 0.5 )
{
ROS_ERROR("[Planning Node] path has node in obstacles !");
return make_pair(cubeMax, false);
}
vertex_idx.row(i) = pt_idx;
}
int id_x, id_y, id_z;
/*
P4------------P3
/| /| ^
/ | / | | z
P1--|---------P2 | |
| P8--------|--p7 |
| / | / /--------> y
|/ |/ /
P5------------P6 / x
*/
// Y- now is the left side : (p1 -- p4 -- p8 -- p5) face sweep
// ############################################################################################################
bool collide;
MatrixXi vertex_idx_lst = vertex_idx;
int iter = 0;
while(iter < _max_inflate_iter)
{
collide = false;
int y_lo = max(0, vertex_idx(0, 1) - _step_length);
int y_up = min(_max_y_id, vertex_idx(1, 1) + _step_length);
for(id_y = vertex_idx(0, 1); id_y >= y_lo; id_y-- )
{
if( collide == true)
break;
for(id_x = vertex_idx(0, 0); id_x >= vertex_idx(3, 0); id_x-- )
{
if( collide == true)
break;
for(id_z = vertex_idx(0, 2); id_z >= vertex_idx(4, 2); id_z-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(0, 1) = min(id_y+2, vertex_idx(0, 1));
vertex_idx(3, 1) = min(id_y+2, vertex_idx(3, 1));
vertex_idx(7, 1) = min(id_y+2, vertex_idx(7, 1));
vertex_idx(4, 1) = min(id_y+2, vertex_idx(4, 1));
}
else
vertex_idx(0, 1) = vertex_idx(3, 1) = vertex_idx(7, 1) = vertex_idx(4, 1) = id_y + 1;
// Y+ now is the right side : (p2 -- p3 -- p7 -- p6) face
// ############################################################################################################
collide = false;
for(id_y = vertex_idx(1, 1); id_y <= y_up; id_y++ )
{
if( collide == true)
break;
for(id_x = vertex_idx(1, 0); id_x >= vertex_idx(2, 0); id_x-- )
{
if( collide == true)
break;
for(id_z = vertex_idx(1, 2); id_z >= vertex_idx(5, 2); id_z-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(1, 1) = max(id_y-2, vertex_idx(1, 1));
vertex_idx(2, 1) = max(id_y-2, vertex_idx(2, 1));
vertex_idx(6, 1) = max(id_y-2, vertex_idx(6, 1));
vertex_idx(5, 1) = max(id_y-2, vertex_idx(5, 1));
}
else
vertex_idx(1, 1) = vertex_idx(2, 1) = vertex_idx(6, 1) = vertex_idx(5, 1) = id_y - 1;
// X + now is the front side : (p1 -- p2 -- p6 -- p5) face
// ############################################################################################################
int x_lo = max(0, vertex_idx(3, 0) - _step_length);
int x_up = min(_max_x_id, vertex_idx(0, 0) + _step_length);
collide = false;
for(id_x = vertex_idx(0, 0); id_x <= x_up; id_x++ )
{
if( collide == true)
break;
for(id_y = vertex_idx(0, 1); id_y <= vertex_idx(1, 1); id_y++ )
{
if( collide == true)
break;
for(id_z = vertex_idx(0, 2); id_z >= vertex_idx(4, 2); id_z-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(0, 0) = max(id_x-2, vertex_idx(0, 0));
vertex_idx(1, 0) = max(id_x-2, vertex_idx(1, 0));
vertex_idx(5, 0) = max(id_x-2, vertex_idx(5, 0));
vertex_idx(4, 0) = max(id_x-2, vertex_idx(4, 0));
}
else
vertex_idx(0, 0) = vertex_idx(1, 0) = vertex_idx(5, 0) = vertex_idx(4, 0) = id_x - 1;
// X- now is the back side : (p4 -- p3 -- p7 -- p8) face
// ############################################################################################################
collide = false;
for(id_x = vertex_idx(3, 0); id_x >= x_lo; id_x-- )
{
if( collide == true)
break;
for(id_y = vertex_idx(3, 1); id_y <= vertex_idx(2, 1); id_y++ )
{
if( collide == true)
break;
for(id_z = vertex_idx(3, 2); id_z >= vertex_idx(7, 2); id_z-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(3, 0) = min(id_x+2, vertex_idx(3, 0));
vertex_idx(2, 0) = min(id_x+2, vertex_idx(2, 0));
vertex_idx(6, 0) = min(id_x+2, vertex_idx(6, 0));
vertex_idx(7, 0) = min(id_x+2, vertex_idx(7, 0));
}
else
vertex_idx(3, 0) = vertex_idx(2, 0) = vertex_idx(6, 0) = vertex_idx(7, 0) = id_x + 1;
// Z+ now is the above side : (p1 -- p2 -- p3 -- p4) face
// ############################################################################################################
collide = false;
int z_lo = max(0, vertex_idx(4, 2) - _step_length);
int z_up = min(_max_z_id, vertex_idx(0, 2) + _step_length);
for(id_z = vertex_idx(0, 2); id_z <= z_up; id_z++ )
{
if( collide == true)
break;
for(id_y = vertex_idx(0, 1); id_y <= vertex_idx(1, 1); id_y++ )
{
if( collide == true)
break;
for(id_x = vertex_idx(0, 0); id_x >= vertex_idx(3, 0); id_x-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(0, 2) = max(id_z-2, vertex_idx(0, 2));
vertex_idx(1, 2) = max(id_z-2, vertex_idx(1, 2));
vertex_idx(2, 2) = max(id_z-2, vertex_idx(2, 2));
vertex_idx(3, 2) = max(id_z-2, vertex_idx(3, 2));
}
vertex_idx(0, 2) = vertex_idx(1, 2) = vertex_idx(2, 2) = vertex_idx(3, 2) = id_z - 1;
// now is the below side : (p5 -- p6 -- p7 -- p8) face
// ############################################################################################################
collide = false;
for(id_z = vertex_idx(4, 2); id_z >= z_lo; id_z-- )
{
if( collide == true)
break;
for(id_y = vertex_idx(4, 1); id_y <= vertex_idx(5, 1); id_y++ )
{
if( collide == true)
break;
for(id_x = vertex_idx(4, 0); id_x >= vertex_idx(7, 0); id_x-- )
{
double occupy = collision_map->Get( (int64_t)id_x, (int64_t)id_y, (int64_t)id_z).first.occupancy;
if(occupy > 0.5) // the voxel is occupied
{
collide = true;
break;
}
}
}
}
if(collide)
{
vertex_idx(4, 2) = min(id_z+2, vertex_idx(4, 2));
vertex_idx(5, 2) = min(id_z+2, vertex_idx(5, 2));
vertex_idx(6, 2) = min(id_z+2, vertex_idx(6, 2));
vertex_idx(7, 2) = min(id_z+2, vertex_idx(7, 2));
}
else
vertex_idx(4, 2) = vertex_idx(5, 2) = vertex_idx(6, 2) = vertex_idx(7, 2) = id_z + 1;
if(vertex_idx_lst == vertex_idx)
break;
vertex_idx_lst = vertex_idx;
MatrixXd vertex_coord(8, 3);
for(int i = 0; i < 8; i++)
{
int index_x = max(min(vertex_idx(i, 0), _max_x_id - 1), 0);
int index_y = max(min(vertex_idx(i, 1), _max_y_id - 1), 0);
int index_z = max(min(vertex_idx(i, 2), _max_z_id - 1), 0);
Vector3i index(index_x, index_y, index_z);
Vector3d pos = collision_map->GridIndexToLocation(index);
vertex_coord.row(i) = pos;
}
cubeMax.setVertex(vertex_coord, _resolution);
if( isContains(lstcube, cubeMax))
return make_pair(lstcube, false);
iter ++;
}
return make_pair(cubeMax, true);
}
Cube generateCube( Vector3d pt)
{
/*
P4------------P3
/| /| ^
/ | / | | z
P1--|---------P2 | |
| P8--------|--p7 |
| / | / /--------> y
|/ |/ /
P5------------P6 / x
*/
Cube cube;
pt(0) = max(min(pt(0), _pt_max_x), _pt_min_x);
pt(1) = max(min(pt(1), _pt_max_y), _pt_min_y);
pt(2) = max(min(pt(2), _pt_max_z), _pt_min_z);
Vector3i pc_index = collision_map->LocationToGridIndex(pt);
Vector3d pc_coord = collision_map->GridIndexToLocation(pc_index);
cube.center = pc_coord;
double x_u = pc_coord(0);
double x_l = pc_coord(0);
double y_u = pc_coord(1);
double y_l = pc_coord(1);
double z_u = pc_coord(2);
double z_l = pc_coord(2);
cube.vertex.row(0) = Vector3d(x_u, y_l, z_u);
cube.vertex.row(1) = Vector3d(x_u, y_u, z_u);
cube.vertex.row(2) = Vector3d(x_l, y_u, z_u);
cube.vertex.row(3) = Vector3d(x_l, y_l, z_u);
cube.vertex.row(4) = Vector3d(x_u, y_l, z_l);
cube.vertex.row(5) = Vector3d(x_u, y_u, z_l);
cube.vertex.row(6) = Vector3d(x_l, y_u, z_l);
cube.vertex.row(7) = Vector3d(x_l, y_l, z_l);
return cube;
}
bool isContains(Cube cube1, Cube cube2)
{
if( cube1.vertex(0, 0) >= cube2.vertex(0, 0) && cube1.vertex(0, 1) <= cube2.vertex(0, 1) && cube1.vertex(0, 2) >= cube2.vertex(0, 2) &&
cube1.vertex(6, 0) <= cube2.vertex(6, 0) && cube1.vertex(6, 1) >= cube2.vertex(6, 1) && cube1.vertex(6, 2) <= cube2.vertex(6, 2) )
return true;
else
return false;
}
void corridorSimplify(vector<Cube> & cubicList)
{
vector<Cube> cubicSimplifyList;
for(int j = (int)cubicList.size() - 1; j >= 0; j--)
{
for(int k = j - 1; k >= 0; k--)
{
if(cubicList[k].valid == false)
continue;
else if(isContains(cubicList[j], cubicList[k]))
cubicList[k].valid = false;
}
}
for(auto cube:cubicList)
if(cube.valid == true)
cubicSimplifyList.push_back(cube);
cubicList = cubicSimplifyList;
}
vector<Cube> corridorGeneration(vector<Vector3d> path_coord, vector<double> time)
{
vector<Cube> cubeList;
Vector3d pt;
Cube lstcube;
for (int i = 0; i < (int)path_coord.size(); i += 1)
{
pt = path_coord[i];
Cube cube = generateCube(pt);
auto result = inflateCube(cube, lstcube);
if(result.second == false)
continue;
cube = result.first;
lstcube = cube;
cube.t = time[i];
cubeList.push_back(cube);
}
return cubeList;
}
vector<Cube> corridorGeneration(vector<Vector3d> path_coord)
{
vector<Cube> cubeList;
Vector3d pt;
Cube lstcube;
for (int i = 0; i < (int)path_coord.size(); i += 1)
{
pt = path_coord[i];
Cube cube = generateCube(pt);
auto result = inflateCube(cube, lstcube);
if(result.second == false)
continue;
cube = result.first;
lstcube = cube;
cubeList.push_back(cube);
}
return cubeList;
}
double velMapping(double d, double max_v)
{
double vel;
if( d <= 0.25)
vel = 2.0 * d * d;
else if(d > 0.25 && d <= 0.75)
vel = 1.5 * d - 0.25;
else if(d > 0.75 && d <= 1.0)
vel = - 2.0 * (d - 1.0) * (d - 1.0) + 1;
else
vel = 1.0;
return vel * max_v;
}
void trajPlanning()
{
if( _has_target == false || _has_map == false || _has_odom == false)
return;
vector<Cube> corridor;
if(_is_use_fm)
{
ros::Time time_1 = ros::Time::now();
float oob_value = INFINITY;
auto EDT = collision_map_local->ExtractDistanceField(oob_value);
ros::Time time_2 = ros::Time::now();
ROS_WARN("time in generate EDT is %f", (time_2 - time_1).toSec());
unsigned int idx;
double max_vel = _MAX_Vel * 0.75;
vector<unsigned int> obs;
Vector3d pt;
vector<int64_t> pt_idx;
double flow_vel;
unsigned int size_x = (unsigned int)(_max_x_id);
unsigned int size_y = (unsigned int)(_max_y_id);
unsigned int size_z = (unsigned int)(_max_z_id);
Coord3D dimsize {size_x, size_y, size_z};
FMGrid3D grid_fmm(dimsize);
for(unsigned int k = 0; k < size_z; k++)
{
for(unsigned int j = 0; j < size_y; j++)
{
for(unsigned int i = 0; i < size_x; i++)
{
idx = k * size_y * size_x + j * size_x + i;
pt << (i + 0.5) * _resolution + _map_origin(0),
(j + 0.5) * _resolution + _map_origin(1),
(k + 0.5) * _resolution + _map_origin(2);
Vector3i index = collision_map_local->LocationToGridIndex(pt);
if(collision_map_local->Inside(index))
{
double d = sqrt(EDT.GetImmutable(index).first.distance_square) * _resolution;
flow_vel = velMapping(d, max_vel);
}
else
flow_vel = max_vel;
if( k == 0 || k == (size_z - 1) || j == 0 || j == (size_y - 1) || i == 0 || i == (size_x - 1) )
flow_vel = 0.0;
grid_fmm[idx].setOccupancy(flow_vel);
if (grid_fmm[idx].isOccupied())
obs.push_back(idx);
}
}
}
grid_fmm.setOccupiedCells(std::move(obs));
grid_fmm.setLeafSize(_resolution);
Vector3d startIdx3d = (_start_pt - _map_origin) * _inv_resolution;
Vector3d endIdx3d = (_end_pt - _map_origin) * _inv_resolution;
Coord3D goal_point = {(unsigned int)startIdx3d[0], (unsigned int)startIdx3d[1], (unsigned int)startIdx3d[2]};
Coord3D init_point = {(unsigned int)endIdx3d[0], (unsigned int)endIdx3d[1], (unsigned int)endIdx3d[2]};
unsigned int startIdx;
vector<unsigned int> startIndices;
grid_fmm.coord2idx(init_point, startIdx);
startIndices.push_back(startIdx);
unsigned int goalIdx;
grid_fmm.coord2idx(goal_point, goalIdx);
grid_fmm[goalIdx].setOccupancy(max_vel);
Solver<FMGrid3D>* fm_solver = new FMMStar<FMGrid3D>("FMM*_Dist", TIME); // LSM, FMM
fm_solver->setEnvironment(&grid_fmm);
fm_solver->setInitialAndGoalPoints(startIndices, goalIdx);
ros::Time time_bef_fm = ros::Time::now();
if(fm_solver->compute(max_vel) == -1)
{
ROS_WARN("[Fast Marching Node] No path can be found");
_traj.action = quadrotor_msgs::PolynomialTrajectory::ACTION_WARN_IMPOSSIBLE;
_traj_pub.publish(_traj);
_has_traj = false;
return;
}
ros::Time time_aft_fm = ros::Time::now();
ROS_WARN("[Fast Marching Node] Time in Fast Marching computing is %f", (time_aft_fm - time_bef_fm).toSec() );
Path3D path3D;
vector<double> path_vels, time;
GradientDescent< FMGrid3D > grad3D;
grid_fmm.coord2idx(goal_point, goalIdx);
if(grad3D.gradient_descent(grid_fmm, goalIdx, path3D, path_vels, time) == -1)
{
ROS_WARN("[Fast Marching Node] FMM failed, valid path not exists");
if(_has_traj && _is_emerg)
{
_traj.action = quadrotor_msgs::PolynomialTrajectory::ACTION_WARN_IMPOSSIBLE;
_traj_pub.publish(_traj);
_has_traj = false;
}
return;
}
vector<Vector3d> path_coord;
path_coord.push_back(_start_pt);
double coord_x, coord_y, coord_z;
for( int i = 0; i < (int)path3D.size(); i++)
{
coord_x = max(min( (path3D[i][0]+0.5) * _resolution + _map_origin(0), _x_size), -_x_size);
coord_y = max(min( (path3D[i][1]+0.5) * _resolution + _map_origin(1), _y_size), -_y_size);
coord_z = max(min( (path3D[i][2]+0.5) * _resolution, _z_size), 0.0);
Vector3d pt(coord_x, coord_y, coord_z);
path_coord.push_back(pt);
}
visPath(path_coord);
ros::Time time_bef_corridor = ros::Time::now();
sortPath(path_coord, time);
corridor = corridorGeneration(path_coord, time);
ros::Time time_aft_corridor = ros::Time::now();
ROS_WARN("Time consume in corridor generation is %f", (time_aft_corridor - time_bef_corridor).toSec());
timeAllocation(corridor, time);
visCorridor(corridor);
delete fm_solver;
}
else
{
path_finder->linkLocalMap(collision_map_local, _local_origin);
path_finder->AstarSearch(_start_pt, _end_pt);
vector<Vector3d> gridPath = path_finder->getPath();
vector<GridNodePtr> searchedNodes = path_finder->getVisitedNodes();
path_finder->resetLocalMap();
visGridPath(gridPath);
visExpNode(searchedNodes);
ros::Time time_bef_corridor = ros::Time::now();
corridor = corridorGeneration(gridPath);
ros::Time time_aft_corridor = ros::Time::now();
ROS_WARN("Time consume in corridor generation is %f", (time_aft_corridor - time_bef_corridor).toSec());
timeAllocation(corridor);
visCorridor(corridor);
}
MatrixXd pos = MatrixXd::Zero(2,3);
MatrixXd vel = MatrixXd::Zero(2,3);
MatrixXd acc = MatrixXd::Zero(2,3);
pos.row(0) = _start_pt;
pos.row(1) = _end_pt;
vel.row(0) = _start_vel;
acc.row(0) = _start_acc;
double obj;
ros::Time time_bef_opt = ros::Time::now();
if(_trajectoryGenerator.BezierPloyCoeffGeneration
( corridor, _MQM, pos, vel, acc, _MAX_Vel, _MAX_Acc, _traj_order, _minimize_order,
_cube_margin, _is_limit_vel, _is_limit_acc, obj, _bezier_coeff ) == -1 )
{
ROS_WARN("Cannot find a feasible and optimal solution, somthing wrong with the mosek solver");
if(_has_traj && _is_emerg)
{
_traj.action = quadrotor_msgs::PolynomialTrajectory::ACTION_WARN_IMPOSSIBLE;
_traj_pub.publish(_traj);
_has_traj = false;
}
}
else
{
_seg_num = corridor.size();
_seg_time.resize(_seg_num);
for(int i = 0; i < _seg_num; i++)
_seg_time(i) = corridor[i].t;
_is_emerg = false;
_has_traj = true;
_traj = getBezierTraj();