-
Notifications
You must be signed in to change notification settings - Fork 89
/
main.cpp
480 lines (390 loc) · 16.7 KB
/
main.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
//xugong5 problem:
//1 tracking miss
//2 tf_old_data and process die
//xugong6 solve tf_old_data problem , tf::TransformListener lr(ros::Duration(100));
// changshu_2 base on xugong6 ,change parameter related with vehicle ,Lidar height
#include <ros/ros.h>
#include <sensor_msgs/point_cloud_conversion.h>
#include <sensor_msgs/PointCloud2.h>
#include "sensor_msgs/Imu.h"
#include <visualization_msgs/Marker.h>
// PCL specific includes
#include <pcl/io/pcd_io.h>
#include <pcl_conversions/pcl_conversions.h>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl/common/transforms.h>
#include <pcl_ros/transforms.h>
#include "pcl_ros/impl/transforms.hpp"
// #include <pcl_ros/transforms.h>
#include <vector>
#include <iostream>
#include <math.h>
#include <nav_msgs/Odometry.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include "tf/transform_datatypes.h"
#include <tf2/LinearMath/Quaternion.h>
#include <tf2_ros/transform_broadcaster.h>
// #include <tf2_ros/buffer.h>
// #include <tf2/transform_datatypes.h>
// #include <tf2_sensor_msgs/tf2_sensor_msgs.h>
// #include <message_filters/subscriber.h>
// #include <message_filters/time_synchronizer.h>
// #include <message_filters/sync_policies/approximate_time.h>
#include <object_tracking/trackbox.h>
#include "imm_ukf_jpda.h"
using namespace std;
using namespace Eigen;
using namespace pcl;
// using namespace message_filters;
int counta = 0;
ros::Publisher pub;
ros::Publisher vis_pub;
ros::Publisher vis_pub2;
tf::TransformListener* tran;
// tf::TransformListener* tran2;
double yaw_gps;
double v_gps;
// 回调函数-- 话题 track_box
void cloud_cb (const object_tracking::trackbox& input){
counta ++;
cout << "Frame: "<<counta << "----------------------------------------"<< endl;
// convert local to global-------------------------
double timestamp = input.header.stamp.toSec(); // 报错: error: cannot convert ‘const _stamp_type {aka const ros::Time}’ to ‘double’
vector<vector<double>> egoPoints;
getOriginPoints(timestamp, egoPoints,v_gps,yaw_gps); // v_gps,yaw_gps都是从回调函数cloud_cb计算得来
static tf::TransformBroadcaster br;
tf::Transform transform;
transform.setOrigin( tf::Vector3(egoPoints[0][0], egoPoints[0][1], 0.0) );
tf::Quaternion q;
ros::Time input_time = input.header.stamp;
q.setRPY(0, 0, egoPoints[0][2]);
transform.setRotation(q);
br.sendTransform(tf::StampedTransform(transform, input_time, "velodyne", "global"));
// br.sendTransform(tf::StampedTransform(transform, input_time, "velo_link", "global"));
// cout << "transform "<< egoPoints[0][0] << " "<<egoPoints[0][1]<< " "<<egoPoints[0][2]<<endl;
// tf::StampedTransform transform2;
// try{
// tran->lookupTransform("/global", "/velodyne", input_time, transform2);
// }
// catch (tf::TransformException &ex) {
// ROS_ERROR("%s",ex.what());
// }
// tf::StampedTransform transform2;
int box_num = input.box_num;
vector<PointCloud<PointXYZ>> bBoxes;
PointCloud<PointXYZ> oneBbox;
// bBoxes.header = input.header;
for(int box_i = 0;box_i < box_num; box_i++)
{
PointXYZ o;
o.x = input.x1[3*box_i];
o.y = input.x1[3*box_i + 1];
o.z = input.x1[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.x2[3*box_i];
o.y = input.x2[3*box_i + 1];
o.z = input.x2[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.x3[3*box_i + 0];
o.y = input.x3[3*box_i + 1];
o.z = input.x3[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.x4[3*box_i + 0];
o.y = input.x4[3*box_i + 1];
o.z = input.x4[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.y1[3*box_i + 0];
o.y = input.y1[3*box_i + 1];
o.z = input.y1[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.y2[3*box_i + 0];
o.y = input.y2[3*box_i + 1];
o.z = input.y2[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.y3[3*box_i + 0];
o.y = input.y3[3*box_i + 1];
o.z = input.y3[3*box_i + 2];
oneBbox.push_back(o);
o.x = input.y4[3*box_i + 0];
o.y = input.y4[3*box_i + 1];
o.z = input.y4[3*box_i + 2];
oneBbox.push_back(o);
bBoxes.push_back(oneBbox);
oneBbox.clear();
}
PointCloud<PointXYZ> newBox;
for(int i = 0; i < bBoxes.size(); i++ ){
// cout << "before converting "<<getCpFromBbox(bBoxes[i])(0) << " "<<getCpFromBbox(bBoxes[i])(1)<<endl;
bBoxes[i].header.frame_id = "velodyne";
// bBoxes[i].header.frame_id = "velo_link";
// try {
// tran->waitForTransform("/global", "/velodyne", input_time, ros::Duration(10.0));
// tran->lookupTransform("/global", "/velodyne", input_time, transform2);
// } catch (tf::TransformException ex) {
// ROS_ERROR("%s",ex.what());
// }
tran->waitForTransform("/global", "/velodyne", input_time, ros::Duration(10.0));
// tran->waitForTransform("/global", "/velo_link", input_time, ros::Duration(10.0));
pcl_ros::transformPointCloud("/global", bBoxes[i], newBox, *tran);
bBoxes[i] = newBox;
}
//end converting----------------------------------------
PointCloud<PointXYZ> targetPoints;
vector<vector<double>> targetVandYaw;
vector<int> trackManage; // trackManage??? 大量具有相关不确定性的跟踪对象需要有效地实施跟踪管理。跟踪管理的主要目的是动态限制虚假跟踪列表的数量(从而防止错误的数据关联),并在丢失检测的情况下保持对象跟踪
vector<bool> isStaticVec;
vector<bool> isVisVec;
vector<PointCloud<PointXYZ>> visBBs;
immUkfJpdaf(bBoxes, timestamp, targetPoints, targetVandYaw, trackManage, isStaticVec, isVisVec, visBBs);
// cout << "size is "<<visBBs.size()<<endl;
// cout << "x1:"<<visBBs[0][0].x<<"y1:"<<visBBs[0][0].y<<endl;
// cout << "x2:"<<visBBs[0][1].x<<"y2:"<<visBBs[0][1].y<<endl;
// cout << "x3:"<<visBBs[0][2].x<<"y3:"<<visBBs[0][2].y<<endl;
// cout << "x4:"<<visBBs[0][3].x<<"y4:"<<visBBs[0][3].y<<endl;
assert(targetPoints.size() == trackManage.size());
assert(targetPoints.size()== targetVandYaw.size());
// converting from global to ego tf for visualization
// processing targetPoints
PointCloud<PointXYZ> egoTFPoints;
targetPoints.header.frame_id = "global";
pcl_ros::transformPointCloud("/velodyne", targetPoints, egoTFPoints, *tran);
// pcl_ros::transformPointCloud("/velo_link", targetPoints, egoTFPoints, *tran);
//processing visBBs
PointCloud<PointXYZ> visEgoBB;
for(int i = 0; i < visBBs.size(); i++){
visBBs[i].header.frame_id = "global";
pcl_ros::transformPointCloud("/velodyne", visBBs[i], visEgoBB, *tran);
// pcl_ros::transformPointCloud("/velo_link", visBBs[i], visEgoBB, *tran);
visBBs[i] = visEgoBB;
}
//end converting to ego tf-------------------------
// tracking arrows visualizing start---------------------------------------------
for(int i = 0; i < targetPoints.size(); i++){
visualization_msgs::Marker arrowsG;
arrowsG.lifetime = ros::Duration(0.1);
if(trackManage[i] == 0 ) {
continue;
}
if(isVisVec[i] == false ) {
continue;
}
if(isStaticVec[i] == true){
continue;
}
// arrowsG.header.frame_id = "/velo_link";
arrowsG.header.frame_id = "/velodyne";
arrowsG.header.stamp= ros::Time::now();
arrowsG.ns = "arrows";
arrowsG.action = visualization_msgs::Marker::ADD;
arrowsG.type = visualization_msgs::Marker::ARROW;
// green 设置颜色
arrowsG.color.g = 1.0f; // 绿色
// arrowsG.color.r = 1.0f; // 红色
arrowsG.color.a = 1.0;
arrowsG.id = i;
geometry_msgs::Point p;
// assert(targetPoints[i].size()==4);
p.x = egoTFPoints[i].x;
p.y = egoTFPoints[i].y;
p.z = -1.73/2;
double tv = targetVandYaw[i][0];
double tyaw = targetVandYaw[i][1];
// Set the pose of the marker. This is a full 6DOF pose relative to the frame/time specified in the header
arrowsG.pose.position.x = p.x;
arrowsG.pose.position.y = p.y;
arrowsG.pose.position.z = p.z;
// convert from 3 angles to quartenion
tf::Matrix3x3 obs_mat;
obs_mat.setEulerYPR(tyaw, 0, 0); // yaw, pitch, roll
tf::Quaternion q_tf;
obs_mat.getRotation(q_tf);
arrowsG.pose.orientation.x = q_tf.getX();
arrowsG.pose.orientation.y = q_tf.getY();
arrowsG.pose.orientation.z = q_tf.getZ();
arrowsG.pose.orientation.w = q_tf.getW();
// Set the scale of the arrowsG -- 1x1x1 here means 1m on a side
arrowsG.scale.x = tv;
arrowsG.scale.y = 0.1;
arrowsG.scale.z = 0.1;
vis_pub.publish(arrowsG); // 发布箭头消息
}
// tracking points visualizing start---------------------------------------------
visualization_msgs::Marker pointsY, pointsG, pointsR, pointsB;
pointsY.header.frame_id = pointsG.header.frame_id = pointsR.header.frame_id = pointsB.header.frame_id = "velodyne";
// pointsY.header.frame_id = pointsG.header.frame_id = pointsR.header.frame_id = pointsB.header.frame_id = "velo_link";
pointsY.header.stamp= pointsG.header.stamp= pointsR.header.stamp =pointsB.header.stamp = ros::Time::now();
pointsY.ns= pointsG.ns = pointsR.ns =pointsB.ns= "points";
pointsY.action = pointsG.action = pointsR.action = pointsB.action = visualization_msgs::Marker::ADD;
pointsY.pose.orientation.w = pointsG.pose.orientation.w = pointsR.pose.orientation.w =pointsB.pose.orientation.w= 1.0;
pointsY.id = 1;
pointsG.id = 2;
pointsR.id = 3;
pointsB.id = 4;
pointsY.type = pointsG.type = pointsR.type = pointsB.type = visualization_msgs::Marker::POINTS;
// POINTS markers use x and y scale for width/height respectively
pointsY.scale.x =pointsG.scale.x =pointsR.scale.x = pointsB.scale.x=0.5;
pointsY.scale.y =pointsG.scale.y =pointsR.scale.y = pointsB.scale.y = 0.5;
// yellow(红绿蓝混合为黄)
pointsY.color.r = 1.0f;
pointsY.color.g = 1.0f;
pointsY.color.b = 0.0f;
pointsY.color.a = 1.0;
// green
pointsG.color.g = 1.0f;
pointsG.color.a = 1.0;
// red
pointsR.color.r = 1.0;
pointsR.color.a = 1.0;
// blue
pointsB.color.b = 1.0;
pointsB.color.a = 1.0;
// cout << "targetPoints.size() is --=------" << targetPoints.size() <<endl;
for(int i = 0; i < targetPoints.size(); i++){
if(trackManage[i] == 0) continue;
geometry_msgs::Point p;
// p.x = targetPoints[i].x;
// p.y = targetPoints[i].y;
p.x = egoTFPoints[i].x;
p.y = egoTFPoints[i].y;
p.z = -1.73/2;
// cout << "is ------------------" << i <<endl;
// cout << "trackManage[i] " <<trackManage[i] << endl; // 输出
if(isStaticVec[i] == true){ // isStaticVec???
pointsB.points.push_back(p); // 蓝点
}
else if(trackManage[i] < 5 ){ // 小于5为黄点
pointsY.points.push_back(p);
}
else if(trackManage[i] == 5){ // 等于5为绿点
pointsG.points.push_back(p);
}
else if(trackManage[i] > 5){
pointsR.points.push_back(p); // 大于5为红点
}
}
vis_pub.publish(pointsY); // 发布
// cout << "pointsG" << pointsG.points[0].x << " "<< pointsG.points[0].y << endl;
vis_pub.publish(pointsG); // 发布
vis_pub.publish(pointsR); // 发布
vis_pub.publish(pointsB); // 发布
// tracking poiints visualizing end---------------------------------------------
// // bounding box visualizing start---------------------------------------------
// visualization_msgs::Marker line_list;
// // line_list.header.frame_id = "velo_link";
// line_list.header.frame_id = "velodyne";
// line_list.header.stamp = ros::Time::now();
// line_list.ns = "boxes";
// line_list.action = visualization_msgs::Marker::ADD;
// line_list.pose.orientation.w = 1.0;
// line_list.id = 0;
// line_list.type = visualization_msgs::Marker::LINE_LIST;
// //LINE_LIST markers use only the x component of scale, for the line width
// line_list.scale.x = 0.1;
// // Points are green
// line_list.color.g = 1.0f;
// line_list.color.a = 1.0;
// int id = 0;string ids;
// for(int objectI = 0; objectI < visBBs.size(); objectI ++){
// for(int pointI = 0; pointI < 4; pointI++){
// assert((pointI+1)%4 < visBBs[objectI].size());
// assert((pointI+4) < visBBs[objectI].size());
// assert((pointI+1)%4+4 < visBBs[objectI].size());
// id ++; ids = to_string(id);
// geometry_msgs::Point p;
// p.x = visBBs[objectI][pointI].x;
// p.y = visBBs[objectI][pointI].y;
// p.z = visBBs[objectI][pointI].z;
// line_list.points.push_back(p);
// p.x = visBBs[objectI][(pointI+1)%4].x;
// p.y = visBBs[objectI][(pointI+1)%4].y;
// p.z = visBBs[objectI][(pointI+1)%4].z;
// line_list.points.push_back(p);
// p.x = visBBs[objectI][pointI].x;
// p.y = visBBs[objectI][pointI].y;
// p.z = visBBs[objectI][pointI].z;
// line_list.points.push_back(p);
// p.x = visBBs[objectI][pointI+4].x;
// p.y = visBBs[objectI][pointI+4].y;
// p.z = visBBs[objectI][pointI+4].z;
// line_list.points.push_back(p);
// p.x = visBBs[objectI][pointI+4].x;
// p.y = visBBs[objectI][pointI+4].y;
// p.z = visBBs[objectI][pointI+4].z;
// line_list.points.push_back(p);
// p.x = visBBs[objectI][(pointI+1)%4+4].x;
// p.y = visBBs[objectI][(pointI+1)%4+4].y;
// p.z = visBBs[objectI][(pointI+1)%4+4].z;
// line_list.points.push_back(p);
// }
// }
// //line list end
// vis_pub.publish(line_list);
// bounding box visualizing end------------------------------------------
}
// 回调函数-- 话题 /gps/odom
int test=0;
void cloud_cb2 (const nav_msgs::Odometry msg)
{
test++;
// cout<<test<<endl;
double v_x = msg.twist.twist.linear.x; // 线速度
double v_y = msg.twist.twist.linear.y;
yaw_gps = msg.pose.pose.orientation.z; // 偏航角
v_gps = sqrt(v_x*v_x+v_y*v_y);
// cout << "v_gps: " << v_gps <<endl; //输出 注释 v_gps: 8.03288
// cout<< "yaw_gps: " << yaw_gps <<endl; //输出 注释 yaw_gps: 0
}
int main (int argc, char** argv){
// Initialize ROS
ros::init (argc, argv, "obj_track"); // obj_track--节点
ros::NodeHandle nh;
// ros::Subscriber subImu = nh.subscribe ("imu_data", 10, imu_cb);
tf::TransformListener lr(ros::Duration(100)); //(How long to store transform information)
tran=&lr;
// Create a ROS subscriber for the input point cloud
ros::Subscriber sub = nh.subscribe ("track_box", 160, cloud_cb); //订阅者 track_box -- 话题topic名
ros::Subscriber sub2 = nh.subscribe ("/gps/odom", 1000, cloud_cb2); //订阅者 /gps/odom -- 话题topic名
// message_filters::Subscriber<sensor_msgs::PointCloud2> Velodyne_sub(nh, "/velodyne_points", 1);
// message_filters::Subscriber<nav_msgs::Odometry> odom_sub(nh, "/gps_odom", 1);
// typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, nav_msgs::Odometry> MySyncPolicy;
// message_filters::Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), Velodyne_sub, odom_sub);
// // TimeSynchronizer<sensor_msgs::PointCloud2, nav_msgs::Odometry> sync(Velodyne_sub, odom_sub, 10);
// cout << "start syn" << endl;
// sync.registerCallback(boost::bind(&callback, _1, _2));
// cout << "start syn1" << endl;
// Create a ROS publisher for the output point cloud
pub = nh.advertise<sensor_msgs::PointCloud2> ("output", 1); //发布者 visualization_marker -- 话题topic名
vis_pub = nh.advertise<visualization_msgs::Marker>( "visualization_marker", 0 ); //发布者 visualization_marker -- 话题topic名
vis_pub2 = nh.advertise<visualization_msgs::Marker>( "visualization_marker2", 0 ); //发布者 visualization_marker2 -- 话题topic名
// cout << "start syn3" << endl;
// //TF Broadcasterの実体化
// tf::TransformBroadcaster global_robot_broadcaster;
// //Robot位置と姿勢(x,y,yaw)の取得
// // double x=GetRobotPositionX();
// // double y=GetRobotPositionY();
// // double yaw=GetRobotPositionYaw();
// double x = 0;
// double y = 0;
// double yaw = M_PI/2;
// //yawのデータからクォータニオンを作成
// geometry_msgs::Quaternion robot_quat=tf::createQuaternionMsgFromYaw(yaw);
// //robot座標系の元となるロボットの位置姿勢情報格納用変数の作成
// geometry_msgs::TransformStamped robotState;
//输出 注释
// //現在の時間の格納
// robotState.header.stamp = ros::Time::now();
// //座標系globalとrobotの指定
// robotState.header.frame_id = "global";
// robotState.child_frame_id = "velo_link";
// //global座標系からみたrobot座標系の原点位置と方向の格納
// robotState.transform.translation.x = x;
// robotState.transform.translation.y = y;
// robotState.transform.translation.z = -1.73/2;
// robotState.transform.rotation = robot_quat;
// //tf情報をbroadcast(座標系の設定)
// global_robot_broadcaster.sendTransform(robotState);
// Spin
ros::spin ();
}