imm_ukf_pda.cpp 34 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015
  1. /*
  2. * Copyright 2018-2019 Autoware Foundation. All rights reserved.
  3. *
  4. * Licensed under the Apache License, Version 2.0 (the "License");
  5. * you may not use this file except in compliance with the License.
  6. * You may obtain a copy of the License at
  7. *
  8. * http://www.apache.org/licenses/LICENSE-2.0
  9. *
  10. * Unless required by applicable law or agreed to in writing, software
  11. * distributed under the License is distributed on an "AS IS" BASIS,
  12. * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  13. * See the License for the specific language governing permissions and
  14. * limitations under the License.
  15. */
  16. #include "imm_ukf_pda.h"
  17. #include "modulecomm.h"
  18. #include "ivlog.h"
  19. extern iv::Ivlog *givlog;
  20. extern void * gpatrack;
  21. ImmUkfPda::ImmUkfPda()
  22. : target_id_(0)
  23. , // assign unique ukf_id_ to each tracking targets
  24. init_(false),
  25. frame_count_(0),
  26. has_subscribed_vectormap_(false)
  27. {
  28. tracking_frame_ = "world";
  29. life_time_thres_ = 8;
  30. gating_thres_ = 9.22;
  31. gate_probability_ = 0.99;
  32. detection_probability_ = 0.9;
  33. static_velocity_thres_ = 0.5;
  34. static_num_history_thres_ = 3;
  35. prevent_explosion_thres_ = 1000;
  36. merge_distance_threshold_ = 0.5;
  37. use_sukf_ = false;
  38. use_vectormap_ = false;
  39. is_benchmark_ = false;
  40. // private_nh_.param<std::string>("tracking_frame", tracking_frame_, "world");
  41. // private_nh_.param<int>("life_time_thres", life_time_thres_, 8);
  42. // private_nh_.param<double>("gating_thres", gating_thres_, 9.22);
  43. // private_nh_.param<double>("gate_probability", gate_probability_, 0.99);
  44. // private_nh_.param<double>("detection_probability", detection_probability_, 0.9);
  45. // private_nh_.param<double>("static_velocity_thres", static_velocity_thres_, 0.5);
  46. // private_nh_.param<int>("static_velocity_history_thres", static_num_history_thres_, 3);
  47. // private_nh_.param<double>("prevent_explosion_thres", prevent_explosion_thres_, 1000);
  48. // private_nh_.param<double>("merge_distance_threshold", merge_distance_threshold_, 0.5);
  49. // private_nh_.param<bool>("use_sukf", use_sukf_, false);
  50. // // for vectormap assisted tracking
  51. // private_nh_.param<bool>("use_vectormap", use_vectormap_, false);
  52. // private_nh_.param<double>("lane_direction_chi_thres", lane_direction_chi_thres_, 2.71);
  53. // private_nh_.param<double>("nearest_lane_distance_thres", nearest_lane_distance_thres_, 1.0);
  54. // private_nh_.param<std::string>("vectormap_frame", vectormap_frame_, "map");
  55. // // rosparam for benchmark
  56. // private_nh_.param<bool>("is_benchmark", is_benchmark_, false);
  57. // private_nh_.param<std::string>("kitti_data_dir", kitti_data_dir_, "");
  58. // if (is_benchmark_)
  59. // {
  60. // result_file_path_ = kitti_data_dir_ + "benchmark_results.txt";
  61. // std::remove(result_file_path_.c_str());
  62. // }
  63. }
  64. void ImmUkfPda::run()
  65. {
  66. // pub_object_array_ = node_handle_.advertise<iv::lidar::objectarray >("/detection/objects", 1);
  67. // sub_detected_array_ = node_handle_.subscribe("/detection/fusion_tools/objects", 1, &ImmUkfPda::callback, this);
  68. // if (use_vectormap_)
  69. // {
  70. // vmap_.subscribe(private_nh_, vector_map::Category::POINT |
  71. // vector_map::Category::NODE |
  72. // vector_map::Category::LANE, 1);
  73. // }
  74. }
  75. void ObsToNormal(iv::fusion::fusionobjectarray& lidar_radar_fusion_object_array)
  76. {
  77. for(int i = 0; i < lidar_radar_fusion_object_array.obj_size(); i++)
  78. {
  79. // if((lidar_radar_fusion_object_array.obj(i).sensor_type() == 0) &&(lidar_radar_fusion_object_array.obj(i).centroid().y() > 20 || abs(lidar_radar_fusion_object_array.obj(i).centroid().x())>10) ) continue;
  80. // if ((lidar_radar_fusion_object_array.obj(i).sensor_type() == 0)&&(lidar_radar_fusion_object_array.obj(i).centroid().y()>10 && abs(lidar_radar_fusion_object_array.obj(i).centroid().x())<1.3)) continue;
  81. // if((lidar_radar_fusion_object_array.obj(i).sensor_type() == 0)&&(lidar_radar_fusion_object_array.obj(i).centroid().y() <1.0 && abs(lidar_radar_fusion_object_array.obj(i).centroid().x())<1.3)) continue;
  82. if((lidar_radar_fusion_object_array.obj(i).dimensions().x()>0)&&
  83. (lidar_radar_fusion_object_array.obj(i).dimensions().y()>0))
  84. {
  85. int xp = (int)((lidar_radar_fusion_object_array.obj(i).dimensions().x()/0.2)/2.0);
  86. if(xp == 0)xp=1;
  87. int yp = (int)((lidar_radar_fusion_object_array.obj(i).dimensions().y()/0.2)/2.0);
  88. if(yp == 0)yp=1;
  89. int ix,iy;
  90. for(ix = 0; ix<(xp*2); ix++)
  91. {
  92. for(iy = 0; iy<(yp*2); iy++)
  93. {
  94. iv::fusion::NomalXYZ nomal_centroid;
  95. iv::fusion::NomalXYZ *nomal_centroid_;
  96. float nomal_x = ix*0.2 - xp*0.2;
  97. float nomal_y = iy*0.2 - yp*0.2;
  98. float nomal_z = 1.0;
  99. float s = nomal_x*cos(lidar_radar_fusion_object_array.obj(i).yaw())
  100. - nomal_y*sin(lidar_radar_fusion_object_array.obj(i).yaw());
  101. float t = nomal_x*sin(lidar_radar_fusion_object_array.obj(i).yaw())
  102. + nomal_y*cos(lidar_radar_fusion_object_array.obj(i).yaw());
  103. nomal_centroid.set_nomal_x(lidar_radar_fusion_object_array.obj(i).centroid().x() + s);
  104. nomal_centroid.set_nomal_y(lidar_radar_fusion_object_array.obj(i).centroid().y() + t);
  105. if(abs(lidar_radar_fusion_object_array.obj(i).centroid().x() + s) <1.3 &&
  106. lidar_radar_fusion_object_array.obj(i).centroid().y() + t <1.0) continue;
  107. else{
  108. nomal_centroid.set_nomal_x(lidar_radar_fusion_object_array.obj(i).centroid().x() + s);
  109. nomal_centroid.set_nomal_y(lidar_radar_fusion_object_array.obj(i).centroid().y() + t);
  110. iv::fusion::fusionobject &fusion_obj = (iv::fusion::fusionobject &)lidar_radar_fusion_object_array.obj(i);
  111. nomal_centroid_ = fusion_obj.add_nomal_centroid();
  112. nomal_centroid_->CopyFrom(nomal_centroid);
  113. }
  114. }
  115. }
  116. }
  117. }}
  118. void ImmUkfPda::callback(const iv::fusion::fusionobjectarray & input)
  119. {
  120. // input_header_ = input.header;
  121. // if(use_vectormap_)
  122. // {
  123. // checkVectormapSubscription();
  124. // }
  125. // bool success = updateNecessaryTransform();
  126. // if (!success)
  127. // {
  128. // ROS_INFO("Could not find coordiante transformation");
  129. // return;
  130. // }
  131. // iv::lidar::objectarray transformed_input;
  132. iv::fusion::fusionobjectarray fused_objects_output;
  133. // transformPoseToGlobal(input, transformed_input);
  134. tracker(input, fused_objects_output);
  135. // transformPoseToLocal(detected_objects_output);
  136. // pub_object_array_.publish(detected_objects_output);
  137. // if (is_benchmark_)
  138. // {
  139. // dumpResultText(detected_objects_output);
  140. // }
  141. }
  142. void ImmUkfPda::checkVectormapSubscription()
  143. {
  144. // if (use_vectormap_ && !has_subscribed_vectormap_)
  145. // {
  146. // lanes_ = vmap_.findByFilter([](const vector_map_msgs::Lane& lane) { return true; });
  147. // if (lanes_.empty())
  148. // {
  149. // ROS_INFO("Has not subscribed vectormap");
  150. // }
  151. // else
  152. // {
  153. // has_subscribed_vectormap_ = true;
  154. // }
  155. // }
  156. }
  157. //bool ImmUkfPda::updateNecessaryTransform()
  158. //{
  159. // bool success = true;
  160. // try
  161. // {
  162. // tf_listener_.waitForTransform(input_header_.frame_id, tracking_frame_, ros::Time(0), ros::Duration(1.0));
  163. // tf_listener_.lookupTransform(tracking_frame_, input_header_.frame_id, ros::Time(0), local2global_);
  164. // }
  165. // catch (tf::TransformException ex)
  166. // {
  167. // ROS_ERROR("%s", ex.what());
  168. // success = false;
  169. // }
  170. // if (use_vectormap_ && has_subscribed_vectormap_)
  171. // {
  172. // try
  173. // {
  174. // tf_listener_.waitForTransform(vectormap_frame_, tracking_frame_, ros::Time(0), ros::Duration(1.0));
  175. // tf_listener_.lookupTransform(vectormap_frame_, tracking_frame_, ros::Time(0), tracking_frame2lane_frame_);
  176. // tf_listener_.lookupTransform(tracking_frame_, vectormap_frame_, ros::Time(0), lane_frame2tracking_frame_);
  177. // }
  178. // catch (tf::TransformException ex)
  179. // {
  180. // ROS_ERROR("%s", ex.what());
  181. // }
  182. // }
  183. // return success;
  184. //}
  185. //void ImmUkfPda::transformPoseToGlobal(const iv::lidar::objectarray & input,
  186. // iv::lidar::objectarray & transformed_input)
  187. //{
  188. // transformed_input.header = input_header_;
  189. // for (auto const &object: input.objects)
  190. // {
  191. // geometry_msgs::Pose out_pose = getTransformedPose(object.pose, local2global_);
  192. // iv::lidar::object dd;
  193. // dd.header = input.header;
  194. // dd = object;
  195. // dd.pose = out_pose;
  196. // transformed_input.objects.push_back(dd);
  197. // }
  198. //}
  199. //void ImmUkfPda::transformPoseToLocal(iv::lidar::objectarray & detected_objects_output)
  200. //{
  201. // detected_objects_output.header = input_header_;
  202. // tf::Transform inv_local2global = local2global_.inverse();
  203. // tf::StampedTransform global2local;
  204. // global2local.setData(inv_local2global);
  205. // for (auto& object : detected_objects_output.objects)
  206. // {
  207. // geometry_msgs::Pose out_pose = getTransformedPose(object.pose, global2local);
  208. // object.header = input_header_;
  209. // object.pose = out_pose;
  210. // }
  211. //}
  212. //geometry_msgs::Pose ImmUkfPda::getTransformedPose(const geometry_msgs::Pose& in_pose,
  213. // const tf::StampedTransform& tf_stamp)
  214. //{
  215. // tf::Transform transform;
  216. // geometry_msgs::PoseStamped out_pose;
  217. // transform.setOrigin(tf::Vector3(in_pose.position.x, in_pose.position().y(), in_pose.position.z));
  218. // transform.setRotation(
  219. // tf::Quaternion(in_pose.orientation.x, in_pose.orientation.y, in_pose.orientation.z, in_pose.orientation.w));
  220. // geometry_msgs::PoseStamped pose_out;
  221. // tf::poseTFToMsg(tf_stamp * transform, out_pose.pose);
  222. // return out_pose.pose;
  223. //}
  224. void ImmUkfPda::measurementValidation(const iv::fusion::fusionobjectarray & input, UKF& target,
  225. const bool second_init, const Eigen::VectorXd& max_det_z,
  226. const Eigen::MatrixXd& max_det_s,
  227. iv::fusion::fusionobjectarray & object_vec,
  228. std::vector<bool>& matching_vec)
  229. {
  230. // alert: different from original imm-pda filter, here picking up most likely measurement
  231. // if making it allows to have more than one measurement, you will see non semipositive definite covariance
  232. bool exists_smallest_nis_object = false;
  233. double smallest_nis = std::numeric_limits<double>::max();
  234. int smallest_nis_ind = 0;
  235. for (size_t i = 0; i < input.obj_size(); i++)
  236. {
  237. double x = input.obj(i).centroid().x();
  238. double y = input.obj(i).centroid().y();
  239. Eigen::VectorXd meas = Eigen::VectorXd(2);
  240. meas << x, y;
  241. Eigen::VectorXd diff = meas - max_det_z;
  242. double nis = diff.transpose() * max_det_s.inverse() * diff;
  243. if (nis < gating_thres_)
  244. {
  245. if (nis < smallest_nis)
  246. {
  247. smallest_nis = nis;
  248. target.object_ = input.obj(i);
  249. smallest_nis_ind = i;
  250. exists_smallest_nis_object = true;
  251. }
  252. }
  253. }
  254. if (exists_smallest_nis_object)
  255. {
  256. matching_vec[smallest_nis_ind] = true;
  257. if (use_vectormap_ && has_subscribed_vectormap_)
  258. {
  259. // iv::lidar::object direction_updated_object;
  260. // bool use_direction_meas =
  261. // updateDirection(smallest_nis, target.object_, direction_updated_object, target);
  262. // if (use_direction_meas)
  263. // {
  264. // object_vec.push_back(direction_updated_object);
  265. // }
  266. // else
  267. // {
  268. // object_vec.push_back(target.object_);
  269. // }
  270. }
  271. else
  272. {
  273. iv::fusion::fusionobject * px = object_vec.add_obj();
  274. px->CopyFrom(target.object_);
  275. // object_vec.push_back(target.object_);
  276. }
  277. }
  278. }
  279. //bool ImmUkfPda::updateDirection(const double smallest_nis, const iv::lidar::object & in_object,
  280. // iv::lidar::object & out_object, UKF& target)
  281. //{
  282. // bool use_lane_direction = false;
  283. // target.is_direction_cv_available_ = false;
  284. // target.is_direction_ctrv_available_ = false;
  285. // bool get_lane_success = storeObjectWithNearestLaneDirection(in_object, out_object);
  286. // if (!get_lane_success)
  287. // {
  288. // return use_lane_direction;
  289. // }
  290. // target.checkLaneDirectionAvailability(out_object, lane_direction_chi_thres_, use_sukf_);
  291. // if (target.is_direction_cv_available_ || target.is_direction_ctrv_available_)
  292. // {
  293. // use_lane_direction = true;
  294. // }
  295. // return use_lane_direction;
  296. //}
  297. //bool ImmUkfPda::storeObjectWithNearestLaneDirection(const iv::lidar::object & in_object,
  298. // iv::lidar::object & out_object)
  299. //{
  300. // geometry_msgs::Pose lane_frame_pose = getTransformedPose(in_object.pose, tracking_frame2lane_frame_);
  301. // double min_dist = std::numeric_limits<double>::max();
  302. // double min_yaw = 0;
  303. // for (auto const& lane : lanes_)
  304. // {
  305. // vector_map_msgs::Node node = vmap_.findByKey(vector_map::Key<vector_map_msgs::Node>(lane.bnid));
  306. // vector_map_msgs::Point point = vmap_.findByKey(vector_map::Key<vector_map_msgs::Point>(node.pid));
  307. // double distance = std::sqrt(std::pow(point.bx - lane_frame_pose.position().y(), 2) +
  308. // std::pow(point.ly - lane_frame_pose.position.x, 2));
  309. // if (distance < min_dist)
  310. // {
  311. // min_dist = distance;
  312. // vector_map_msgs::Node front_node = vmap_.findByKey(vector_map::Key<vector_map_msgs::Node>(lane.fnid));
  313. // vector_map_msgs::Point front_point = vmap_.findByKey(vector_map::Key<vector_map_msgs::Point>(front_node.pid));
  314. // min_yaw = std::atan2((front_point.bx - point.bx), (front_point.ly - point.ly));
  315. // }
  316. // }
  317. // bool success = false;
  318. // if (min_dist < nearest_lane_distance_thres_)
  319. // {
  320. // success = true;
  321. // }
  322. // else
  323. // {
  324. // return success;
  325. // }
  326. // // map yaw in rotation matrix representation
  327. // tf::Quaternion map_quat = tf::createQuaternionFromYaw(min_yaw);
  328. // tf::Matrix3x3 map_matrix(map_quat);
  329. // // vectormap_frame to tracking_frame rotation matrix
  330. // tf::Quaternion rotation_quat = lane_frame2tracking_frame_.getRotation();
  331. // tf::Matrix3x3 rotation_matrix(rotation_quat);
  332. // // rotated yaw in matrix representation
  333. // tf::Matrix3x3 rotated_matrix = rotation_matrix * map_matrix;
  334. // double roll, pitch, yaw;
  335. // rotated_matrix.getRPY(roll, pitch, yaw);
  336. // out_object = in_object;
  337. // out_object.angle = yaw;
  338. // return success;
  339. //}
  340. void ImmUkfPda::updateTargetWithAssociatedObject(const iv::fusion::fusionobjectarray & object_vec,
  341. UKF& target)
  342. {
  343. target.lifetime_++;
  344. // if (!target.object_.label.empty() && target.object_.label !="unknown")
  345. // {
  346. // target.label_ = target.object_.label;
  347. // }
  348. updateTrackingNum(object_vec, target);
  349. if (target.tracking_num_ == TrackingState::Stable || target.tracking_num_ == TrackingState::Occlusion)
  350. {
  351. target.is_stable_ = true;
  352. }
  353. }
  354. void ImmUkfPda::updateBehaviorState(const UKF& target, iv::fusion::fusionobject & object)
  355. {
  356. if (target.mode_prob_cv_ > target.mode_prob_ctrv_ && target.mode_prob_cv_ > target.mode_prob_rm_)
  357. {
  358. object.set_behavior_state(MotionModel::CV);
  359. // object.behavior_state = MotionModel::CV;
  360. }
  361. else if (target.mode_prob_ctrv_ > target.mode_prob_cv_ && target.mode_prob_ctrv_ > target.mode_prob_rm_)
  362. {
  363. object.set_behavior_state(MotionModel::CTRV);
  364. // object.behavior_state = MotionModel::CTRV;
  365. }
  366. else
  367. {
  368. object.set_behavior_state(MotionModel::RM);
  369. // object.behavior_state = MotionModel::RM;
  370. }
  371. }
  372. void ImmUkfPda::initTracker(const iv::fusion::fusionobjectarray & input, double timestamp)
  373. {
  374. for (size_t i = 0; i < input.obj_size(); i++)
  375. {
  376. double px = input.obj(i).centroid().x();
  377. double py = input.obj(i).centroid().y();
  378. Eigen::VectorXd init_meas = Eigen::VectorXd(2);
  379. init_meas << px, py;
  380. UKF ukf;
  381. ukf.initialize(init_meas, timestamp, target_id_);
  382. targets_.push_back(ukf);
  383. target_id_++;
  384. }
  385. timestamp_ = timestamp;
  386. init_ = true;
  387. }
  388. void ImmUkfPda::secondInit(UKF& target, const iv::fusion::fusionobjectarray & object_vec, double dt)
  389. {
  390. if (object_vec.obj_size() == 0)
  391. {
  392. target.tracking_num_ = TrackingState::Die;
  393. return;
  394. }
  395. // record init measurement for env classification
  396. target.init_meas_ << target.x_merge_(0), target.x_merge_(1);
  397. // state update
  398. double target_x = object_vec.obj(0).centroid().x();
  399. double target_y = object_vec.obj(0).centroid().y();
  400. double target_diff_x = target_x - target.x_merge_(0);
  401. double target_diff_y = target_y - target.x_merge_(1);
  402. double target_yaw = atan2(target_diff_y, target_diff_x);
  403. double dist = sqrt(target_diff_x * target_diff_x + target_diff_y * target_diff_y);
  404. double target_v = dist / dt;
  405. while (target_yaw > M_PI)
  406. target_yaw -= 2. * M_PI;
  407. while (target_yaw < -M_PI)
  408. target_yaw += 2. * M_PI;
  409. target.x_merge_(0) = target.x_cv_(0) = target.x_ctrv_(0) = target.x_rm_(0) = target_x;
  410. target.x_merge_(1) = target.x_cv_(1) = target.x_ctrv_(1) = target.x_rm_(1) = target_y;
  411. target.x_merge_(2) = target.x_cv_(2) = target.x_ctrv_(2) = target.x_rm_(2) = target_v;
  412. target.x_merge_(3) = target.x_cv_(3) = target.x_ctrv_(3) = target.x_rm_(3) = target_yaw;
  413. target.tracking_num_++;
  414. return;
  415. }
  416. void ImmUkfPda::updateTrackingNum(const iv::fusion::fusionobjectarray & object_vec, UKF& target)
  417. {
  418. if (object_vec.obj_size() > 0)
  419. {
  420. if (target.tracking_num_ < TrackingState::Stable)
  421. {
  422. target.tracking_num_++;
  423. }
  424. else if (target.tracking_num_ == TrackingState::Stable)
  425. {
  426. target.tracking_num_ = TrackingState::Stable;
  427. }
  428. else if (target.tracking_num_ >= TrackingState::Stable && target.tracking_num_ < TrackingState::Lost)
  429. {
  430. target.tracking_num_ = TrackingState::Stable;
  431. }
  432. else if (target.tracking_num_ == TrackingState::Lost)
  433. {
  434. target.tracking_num_ = TrackingState::Die;
  435. }
  436. }
  437. else
  438. {
  439. if (target.tracking_num_ < TrackingState::Stable)
  440. {
  441. target.tracking_num_ = TrackingState::Die;
  442. }
  443. else if (target.tracking_num_ >= TrackingState::Stable && target.tracking_num_ < TrackingState::Lost)
  444. {
  445. target.tracking_num_++;
  446. }
  447. else if (target.tracking_num_ == TrackingState::Lost)
  448. {
  449. target.tracking_num_ = TrackingState::Die;
  450. }
  451. }
  452. return;
  453. }
  454. bool ImmUkfPda::probabilisticDataAssociation(const iv::fusion::fusionobjectarray & input, const double dt,
  455. std::vector<bool>& matching_vec,
  456. iv::fusion::fusionobjectarray & object_vec, UKF& target)
  457. {
  458. double det_s = 0;
  459. Eigen::VectorXd max_det_z;
  460. Eigen::MatrixXd max_det_s;
  461. bool success = true;
  462. if (use_sukf_)
  463. {
  464. max_det_z = target.z_pred_ctrv_;
  465. max_det_s = target.s_ctrv_;
  466. det_s = max_det_s.determinant();
  467. }
  468. else
  469. {
  470. // find maxDetS associated with predZ
  471. target.findMaxZandS(max_det_z, max_det_s);
  472. det_s = max_det_s.determinant();
  473. }
  474. // prevent ukf not to explode
  475. if (std::isnan(det_s) || det_s > prevent_explosion_thres_)
  476. {
  477. target.tracking_num_ = TrackingState::Die;
  478. success = false;
  479. return success;
  480. }
  481. bool is_second_init;
  482. if (target.tracking_num_ == TrackingState::Init)
  483. {
  484. is_second_init = true;
  485. }
  486. else
  487. {
  488. is_second_init = false;
  489. }
  490. // measurement gating
  491. measurementValidation(input, target, is_second_init, max_det_z, max_det_s, object_vec, matching_vec);
  492. // second detection for a target: update v and yaw
  493. if (is_second_init)
  494. {
  495. secondInit(target, object_vec, dt);
  496. success = false;
  497. return success;
  498. }
  499. updateTargetWithAssociatedObject(object_vec, target);
  500. if (target.tracking_num_ == TrackingState::Die)
  501. {
  502. success = false;
  503. return success;
  504. }
  505. return success;
  506. }
  507. void ImmUkfPda::makeNewTargets(const double timestamp, const iv::fusion::fusionobjectarray & input,
  508. const std::vector<bool>& matching_vec)
  509. {
  510. for (size_t i = 0; i < input.obj_size(); i++)
  511. {
  512. if (matching_vec[i] == false)
  513. {
  514. double px = input.obj(i).centroid().x();
  515. double py = input.obj(i).centroid().y();
  516. Eigen::VectorXd init_meas = Eigen::VectorXd(2);
  517. init_meas << px, py;
  518. UKF ukf;
  519. ukf.initialize(init_meas, timestamp, target_id_);
  520. ukf.object_ = input.obj(i);
  521. targets_.push_back(ukf);
  522. target_id_++;
  523. }
  524. }
  525. }
  526. void ImmUkfPda::staticClassification()
  527. {
  528. for (size_t i = 0; i < targets_.size(); i++)
  529. {
  530. // targets_[i].x_merge_(2) is referred for estimated velocity
  531. double current_velocity = std::abs(targets_[i].x_merge_(2));
  532. targets_[i].vel_history_.push_back(current_velocity);
  533. if (targets_[i].tracking_num_ == TrackingState::Stable && targets_[i].lifetime_ > life_time_thres_)
  534. {
  535. int index = 0;
  536. double sum_vel = 0;
  537. double avg_vel = 0;
  538. for (auto rit = targets_[i].vel_history_.rbegin(); index < static_num_history_thres_; ++rit)
  539. {
  540. index++;
  541. sum_vel += *rit;
  542. }
  543. avg_vel = double(sum_vel / static_num_history_thres_);
  544. if(avg_vel < static_velocity_thres_ && current_velocity < static_velocity_thres_)
  545. {
  546. targets_[i].is_static_ = true;
  547. }
  548. }
  549. }
  550. }
  551. bool
  552. ImmUkfPda::arePointsClose(const iv::fusion::PointXYZ & in_point_a,
  553. const iv::fusion::PointXYZ & in_point_b,
  554. float in_radius)
  555. {
  556. return (fabs(in_point_a.x() - in_point_b.x()) <= in_radius) && (fabs(in_point_a.y() - in_point_b.y()) <= in_radius);
  557. }
  558. bool
  559. ImmUkfPda::arePointsEqual(const iv::fusion::PointXYZ & in_point_a,
  560. const iv::fusion::PointXYZ & in_point_b)
  561. {
  562. return arePointsClose(in_point_a, in_point_b, CENTROID_DISTANCE);
  563. }
  564. bool
  565. ImmUkfPda::isPointInPool(const std::vector<iv::fusion::PointXYZ>& in_pool,
  566. const iv::fusion::PointXYZ& in_point)
  567. {
  568. for(size_t j=0; j<in_pool.size(); j++)
  569. {
  570. if (arePointsEqual(in_pool[j], in_point))
  571. {
  572. return true;
  573. }
  574. }
  575. return false;
  576. }
  577. iv::fusion::fusionobjectarray
  578. ImmUkfPda::removeRedundantObjects(const iv::fusion::fusionobjectarray & in_detected_objects,
  579. const std::vector<size_t> in_tracker_indices)
  580. {
  581. if (in_detected_objects.obj_size() != in_tracker_indices.size())
  582. return in_detected_objects;
  583. iv::fusion::fusionobjectarray resulting_objects;
  584. // resulting_objects.header = in_detected_objects.header;
  585. std::vector<iv::fusion::PointXYZ> centroids;
  586. //create unique points
  587. for(size_t i=0; i<in_detected_objects.obj_size(); i++)
  588. {
  589. if(!isPointInPool(centroids, in_detected_objects.obj(i).centroid()))
  590. {
  591. centroids.push_back(in_detected_objects.obj(i).centroid());
  592. }
  593. }
  594. //assign objects to the points
  595. std::vector<std::vector<size_t>> matching_objects(centroids.size());
  596. for(size_t k=0; k<in_detected_objects.obj_size(); k++)
  597. {
  598. const auto& object=in_detected_objects.obj(k);
  599. for(size_t i=0; i< centroids.size(); i++)
  600. {
  601. if (arePointsClose(object.centroid(), centroids[i], merge_distance_threshold_))
  602. {
  603. matching_objects[i].push_back(k);//store index of matched object to this point
  604. }
  605. }
  606. }
  607. //get oldest object on each point
  608. for(size_t i=0; i< matching_objects.size(); i++)
  609. {
  610. size_t oldest_object_index = 0;
  611. int oldest_lifespan = -1;
  612. std::string best_label;
  613. for(size_t j=0; j<matching_objects[i].size(); j++)
  614. {
  615. size_t current_index = matching_objects[i][j];
  616. int current_lifespan = targets_[in_tracker_indices[current_index]].lifetime_;
  617. if (current_lifespan > oldest_lifespan)
  618. {
  619. oldest_lifespan = current_lifespan;
  620. oldest_object_index = current_index;
  621. }
  622. if (!targets_[in_tracker_indices[current_index]].label_.empty() &&
  623. targets_[in_tracker_indices[current_index]].label_ != "unknown")
  624. {
  625. best_label = targets_[in_tracker_indices[current_index]].label_;
  626. }
  627. }
  628. // delete nearby targets except for the oldest target
  629. for(size_t j=0; j<matching_objects[i].size(); j++)
  630. {
  631. size_t current_index = matching_objects[i][j];
  632. if(current_index != oldest_object_index)
  633. {
  634. targets_[in_tracker_indices[current_index]].tracking_num_= TrackingState::Die;
  635. }
  636. }
  637. iv::fusion::fusionobject best_object;
  638. best_object = in_detected_objects.obj(oldest_object_index);
  639. if (best_label != "unknown"
  640. && !best_label.empty())
  641. {
  642. // best_object.label = best_label;
  643. }
  644. iv::fusion::fusionobject * px = resulting_objects.add_obj();
  645. px->CopyFrom(best_object);
  646. // resulting_objects.push_back(best_object);
  647. }
  648. return resulting_objects;
  649. }
  650. void ImmUkfPda::makeOutput(const iv::fusion::fusionobjectarray & input,
  651. const std::vector<bool> &matching_vec,
  652. iv::fusion::fusionobjectarray & fused_objects_output)
  653. {
  654. iv::fusion::fusionobjectarray tmp_objects;
  655. // tmp_objects.header = input.header;
  656. std::vector<size_t> used_targets_indices;
  657. for (size_t i = 0; i < targets_.size(); i++)
  658. {
  659. double tx = targets_[i].x_merge_(0);
  660. double ty = targets_[i].x_merge_(1);
  661. double tv = targets_[i].x_merge_(2);
  662. double tyaw = targets_[i].x_merge_(3);
  663. double tyaw_rate = targets_[i].x_merge_(4);
  664. if(tyaw_rate > 0.2)
  665. {
  666. tyaw_rate = 0.2;
  667. }
  668. while (tyaw > M_PI)
  669. tyaw -= 2. * M_PI;
  670. while (tyaw < -M_PI)
  671. tyaw += 2. * M_PI;
  672. // tf::Quaternion q = tf::createQuaternionFromYaw(tyaw);
  673. iv::fusion::fusionobject dd;
  674. dd = targets_[i].object_;
  675. dd.set_id(targets_[i].ukf_id_);
  676. // dd.id = targets_[i].ukf_id_;
  677. dd.set_velocity_linear_x(tv);
  678. // dd.velocity_linear_x = tv;
  679. dd.set_acceleration_linear_y(tyaw_rate);
  680. // dd.acceleration_linear_y = tyaw_rate;
  681. dd.set_velocity_reliable(targets_[i].is_stable_);
  682. // dd.velocity_reliable = targets_[i].is_stable_;
  683. dd.set_pose_reliable(targets_[i].is_stable_);
  684. // dd.pose_reliable = targets_[i].is_stable_;
  685. if (!targets_[i].is_static_ && targets_[i].is_stable_)
  686. {
  687. // Aligh the longest side of dimentions with the estimated orientation
  688. if(targets_[i].object_.dimensions().x() < targets_[i].object_.dimensions().y())
  689. {
  690. iv::fusion::Dimension * pd = dd.mutable_dimensions();
  691. pd->set_x(targets_[i].object_.dimensions().x());
  692. pd->set_y(targets_[i].object_.dimensions().y());
  693. // dd.dimensions.x = targets_[i].object_.dimensions.y;
  694. // dd.dimensions.y = targets_[i].object_.dimensions.x;
  695. } else {
  696. iv::fusion::Dimension * pd = dd.mutable_dimensions();
  697. pd->set_x(targets_[i].object_.dimensions().y());
  698. pd->set_y(targets_[i].object_.dimensions().x());
  699. }
  700. iv::fusion::PointXYZ * pp = dd.mutable_centroid();
  701. pp->set_x(tx);
  702. pp->set_y((ty));
  703. // dd.position.x = tx;
  704. // dd.position().y() = ty;
  705. // if (!std::isnan(q[0]))
  706. // dd.pose.orientation.x = q[0];
  707. // if (!std::isnan(q[1]))
  708. // dd.pose.orientation.y = q[1];
  709. // if (!std::isnan(q[2]))
  710. // dd.pose.orientation.z = q[2];
  711. // if (!std::isnan(q[3]))
  712. // dd.pose.orientation.w = q[3];
  713. dd.set_yaw(tyaw);
  714. // dd.tyaw = tyaw;
  715. }
  716. updateBehaviorState(targets_[i], dd);
  717. int xp ,yp;
  718. if(targets_[i].object_.dimensions().x() < targets_[i].object_.dimensions().y())
  719. {
  720. xp = (int)((targets_[i].object_.dimensions().x()/0.2)/2.0);
  721. if(xp == 0)xp=1;
  722. yp = (int)((targets_[i].object_.dimensions().y()/0.2)/2.0);
  723. if(yp == 0)yp=1;
  724. } else {
  725. xp = (int)((targets_[i].object_.dimensions().y()/0.2)/2.0);
  726. if(xp == 0)xp=1;
  727. yp = (int)((targets_[i].object_.dimensions().x()/0.2)/2.0);
  728. if(yp == 0)yp=1;
  729. }
  730. int ix,iy;
  731. for(ix = 0; ix<(xp*2); ix++)
  732. {
  733. // std::cout<<" add normal -------------------------- "<<std::endl;
  734. for(iy = 0; iy<(yp*2); iy++)
  735. {
  736. iv::fusion::NomalXYZ nomal_centroid;
  737. iv::fusion::NomalXYZ *nomal_centroid_;
  738. float nomal_x = ix*0.2 - xp*0.2;
  739. float nomal_y = iy*0.2 - yp*0.2;
  740. float nomal_z = 0.5;
  741. float s = nomal_x*cos(0) -
  742. nomal_y*sin(0);
  743. float t = nomal_x*sin(0) +
  744. nomal_y*cos(0);
  745. nomal_centroid.set_nomal_x(tx + s);
  746. nomal_centroid.set_nomal_y(ty + t);
  747. nomal_centroid_ = dd.add_nomal_centroid();
  748. nomal_centroid_->CopyFrom(nomal_centroid);
  749. }
  750. }
  751. if (targets_[i].is_stable_ || (targets_[i].tracking_num_ >= TrackingState::Init &&
  752. targets_[i].tracking_num_ < TrackingState::Stable))
  753. {
  754. iv::fusion::fusionobject * px = tmp_objects.add_obj();
  755. px->CopyFrom(dd);
  756. // tmp_objects.push_back(dd);
  757. used_targets_indices.push_back(i);
  758. }
  759. }
  760. // std::cout<<"run hear."<<std::endl;
  761. fused_objects_output = removeRedundantObjects(tmp_objects, used_targets_indices);
  762. }
  763. void ImmUkfPda::removeUnnecessaryTarget()
  764. {
  765. std::vector<UKF> temp_targets;
  766. for (size_t i = 0; i < targets_.size(); i++)
  767. {
  768. if (targets_[i].tracking_num_ != TrackingState::Die)
  769. {
  770. temp_targets.push_back(targets_[i]);
  771. }
  772. }
  773. std::vector<UKF>().swap(targets_);
  774. targets_ = temp_targets;
  775. }
  776. void ImmUkfPda::dumpResultText(iv::fusion::fusionobjectarray & fused_objects)
  777. {
  778. std::ofstream outputfile(result_file_path_, std::ofstream::out | std::ofstream::app);
  779. for (size_t i = 0; i < fused_objects.obj_size(); i++)
  780. {
  781. // double yaw = tf::getYaw(detected_objects.objects[i].pose.orientation);
  782. double yaw = fused_objects.obj(i).yaw();
  783. // KITTI tracking benchmark data format:
  784. // (frame_number,tracked_id, object type, truncation, occlusion, observation angle, x1,y1,x2,y2, h, w, l, cx, cy,
  785. // cz, yaw)
  786. // x1, y1, x2, y2 are for 2D bounding box.
  787. // h, w, l, are for height, width, length respectively
  788. // cx, cy, cz are for object centroid
  789. // Tracking benchmark is based on frame_number, tracked_id,
  790. // bounding box dimentions and object pose(centroid and orientation) from bird-eye view
  791. outputfile << std::to_string(frame_count_) << " " << std::to_string(fused_objects.obj(i).id()) << " "
  792. << "Unknown"
  793. << " "
  794. << "-1"
  795. << " "
  796. << "-1"
  797. << " "
  798. << "-1"
  799. << " "
  800. << "-1 -1 -1 -1"
  801. << " " << std::to_string(fused_objects.obj(i).dimensions().x()) << " "
  802. << std::to_string(fused_objects.obj(i).dimensions().y()) << " "
  803. << "-1"
  804. << " " << std::to_string(fused_objects.obj(i).centroid().x()) << " "
  805. << std::to_string(fused_objects.obj(i).centroid().y()) << " "
  806. << "-1"
  807. << " " << std::to_string(yaw) << "\n";
  808. }
  809. frame_count_++;
  810. }
  811. void ImmUkfPda::tracker(const iv::fusion::fusionobjectarray & input,
  812. iv::fusion::fusionobjectarray & fused_objects_output)
  813. {
  814. // double timestamp = input.header.stamp.toSec();
  815. if(input.obj_size() < 1)
  816. {
  817. fused_objects_output.set_timestamp(input.timestamp());
  818. std::string out = fused_objects_output.SerializeAsString();
  819. // char * strout = lidarobjtostr(lidarobjvec,ntlen);
  820. iv::modulecomm::ModuleSendMsg(gpatrack,out.data(),out.length());
  821. return;
  822. }
  823. double timestamp = input.timestamp();
  824. // qDebug("time stamp is %f",timestamp);
  825. timestamp = timestamp/1000.0;
  826. std::vector<bool> matching_vec(input.obj_size(), false);
  827. if (!init_)
  828. {
  829. initTracker(input, timestamp);
  830. makeOutput(input, matching_vec, fused_objects_output);
  831. return;
  832. }
  833. double dt = (timestamp - timestamp_);
  834. timestamp_ = timestamp;
  835. // start UKF process
  836. for (size_t i = 0; i < targets_.size(); i++)
  837. {
  838. targets_[i].is_stable_ = false;
  839. targets_[i].is_static_ = false;
  840. if (targets_[i].tracking_num_ == TrackingState::Die)
  841. {
  842. continue;
  843. }
  844. // prevent ukf not to explode
  845. if (targets_[i].p_merge_.determinant() > prevent_explosion_thres_ ||
  846. targets_[i].p_merge_(4, 4) > prevent_explosion_thres_)
  847. {
  848. targets_[i].tracking_num_ = TrackingState::Die;
  849. continue;
  850. }
  851. targets_[i].prediction(use_sukf_, has_subscribed_vectormap_, dt);
  852. iv::fusion::fusionobjectarray object_vec;
  853. bool success = probabilisticDataAssociation(input, dt, matching_vec, object_vec, targets_[i]);
  854. if (!success)
  855. {
  856. continue;
  857. }
  858. targets_[i].update(use_sukf_, detection_probability_, gate_probability_, gating_thres_, object_vec);
  859. }
  860. // end UKF process
  861. // making new ukf target for no data association objects
  862. makeNewTargets(timestamp, input, matching_vec);
  863. // static dynamic classification
  864. staticClassification();
  865. // making output for visualization
  866. makeOutput(input, matching_vec, fused_objects_output);
  867. fused_objects_output.set_timestamp(input.timestamp());
  868. if(fused_objects_output.obj_size()>0)
  869. {
  870. int j;
  871. for(j=0;j<fused_objects_output.obj_size();j++)
  872. {
  873. iv::fusion::fusionobject obj = fused_objects_output.obj(j);
  874. std::cout<<"obj "<<j<< " vel is "<<obj.velocity_linear_x()<<" id is "<<obj.id()<<std::endl;
  875. }
  876. }
  877. else
  878. {
  879. std::cout<<"no obj "<<std::endl;
  880. }
  881. // for(int k =0; k<fused_objects_output.obj_size(); k++ )
  882. // {
  883. // std::cout<<" normal size "<< fused_objects_output.obj(k).nomal_centroid_size()<<std::endl;
  884. // }
  885. // ObsToNormal(fused_objects_output);
  886. std::string out = fused_objects_output.SerializeAsString();
  887. // char * strout = lidarobjtostr(lidarobjvec,ntlen);
  888. iv::modulecomm::ModuleSendMsg(gpatrack,out.data(),out.length());
  889. int i;
  890. for(i=0;i<fused_objects_output.obj_size();i++)
  891. {
  892. iv::fusion::fusionobject * pobj = fused_objects_output.mutable_obj(i);
  893. }
  894. // remove unnecessary ukf object
  895. removeUnnecessaryTarget();
  896. }
  897. void ImmUkfPda::call(const iv::fusion::fusionobjectarray &input)
  898. {
  899. callback(input);
  900. }