obstacle.cpp 27 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760
  1. #include <obstacle/obstacle.h>
  2. #include <geometry_msgs/Point32.h>
  3. #include <sensor_msgs/PointCloud.h>
  4. #include <sensor_msgs/point_cloud_conversion.h>
  5. #include <glog/logging.h>
  6. namespace obs
  7. {
  8. static Json::Value __readLaserConfig()
  9. {
  10. std::string path = space::home() + "configure/obstacle_config.json";
  11. Json::Value c = space::readConfig(path);
  12. return c["sensor"]["laser"];
  13. }
  14. static Json::Value __readCameraConfig()
  15. {
  16. std::string path = space::home() + "configure/obstacle_config.json";
  17. Json::Value c = space::readConfig(path);
  18. return c["sensor"]["camera"];
  19. }
  20. template <typename T>
  21. static bool __interval(const T& value, const T& top, const T& bot)
  22. {
  23. if (value < top && value > bot) return true;
  24. return false;
  25. }
  26. static sensor_msgs::PointCloud __filter3D(sensor_msgs::PointCloud& in, float resolution)
  27. {
  28. sensor_msgs::PointCloud out;
  29. std::map<int, std::map<int, std::map<int, sensor_msgs::PointCloud>>> filter;
  30. for(geometry_msgs::Point32& point : in.points) {
  31. if (fabs(point.x) > 3 || fabs(point.y) > 3 || fabs(point.z) > 3) {
  32. continue;
  33. }
  34. int x = std::ceil(point.x / resolution);
  35. int y = std::ceil(point.y / resolution);
  36. int z = std::ceil(point.z / resolution);
  37. if (filter[x][y][z].points.size() < 6) {
  38. filter[x][y][z].points.push_back(point);
  39. }
  40. else if (filter[x][y][z].points.size() == 6) {
  41. filter[x][y][z].points.push_back(point);
  42. out.points.push_back(point);
  43. }
  44. }
  45. return out;
  46. }
  47. static sensor_msgs::PointCloud __extract3D(sensor_msgs::PointCloud& in, int extract_step)
  48. {
  49. sensor_msgs::PointCloud out;
  50. int step = 0;
  51. for(geometry_msgs::Point32& point : in.points) {
  52. if (step == 0) {
  53. out.points.push_back(point);
  54. }
  55. step++;
  56. if (step > extract_step) {
  57. step = 0;
  58. }
  59. }
  60. return out;
  61. }
  62. /**
  63. * 说明: 对平面点云压缩
  64. * is_gather:是否需要消除孤立点
  65. */
  66. static std::vector<Pose2D> __filter2D(std::vector<Pose2D>& in, float resolution, bool is_gather)
  67. {
  68. std::vector<Pose2D> out;
  69. std::map<int, std::map<int, std::vector<Pose2D>>> filter;
  70. for (Pose2D& pose2d : in) {
  71. int x = std::ceil(pose2d.x / resolution);
  72. int y = std::ceil(pose2d.y / resolution);
  73. if (is_gather) {
  74. if (filter[x][y].size() < 2) {
  75. filter[x][y].push_back(pose2d);
  76. }
  77. else if (filter[x][y].size() == 2) {
  78. filter[x][y].push_back(pose2d);
  79. out.push_back(pose2d);
  80. }
  81. }
  82. else {
  83. if (filter[x][y].empty()) {
  84. filter[x][y].push_back(pose2d);
  85. out.push_back(pose2d);
  86. }
  87. }
  88. }
  89. return out;
  90. }
  91. ObstacleIdentify::ObstacleIdentify() : debug_(true), debug_3d_(false), turn_off_(false), on_(true)
  92. {
  93. }
  94. ObstacleIdentify::~ObstacleIdentify()
  95. {
  96. }
  97. void ObstacleIdentify::start()
  98. {
  99. stop();
  100. __readConfig();
  101. __getPrintFoot();
  102. __registerLaser();
  103. __registerCamera();
  104. point_cloud3D_pub_ = nh_.advertise<sensor_msgs::PointCloud>("/sensor_cloud3D", 10);
  105. debug_ = true;
  106. if (debug_) {
  107. point_cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud>("/sensor_cloud", 10);
  108. dynamic_polygon_pub_ = nh_.advertise<geometry_msgs::PolygonStamped>("/dynamic_polygon", 1, true);
  109. static_polygon_pub_ = nh_.advertise<geometry_msgs::PolygonStamped>("/static_polygon", 1, true);
  110. std::thread pub_thread = std::thread(
  111. [this](){
  112. uint delay = 1000 * 20;
  113. while (ros::ok() && on_) {
  114. std::vector<Pose2D> obstacle = this->__getParseObs();
  115. usleep(delay);
  116. if (obstacle.empty()) {
  117. continue;
  118. }
  119. sensor_msgs::PointCloud laser_point_cloud;
  120. for (const Pose2D& point : obstacle) {
  121. geometry_msgs::Point32 tmp;
  122. tmp.x = point.x;
  123. tmp.y = point.y;
  124. tmp.z = 0;
  125. laser_point_cloud.points.push_back(tmp);
  126. }
  127. laser_point_cloud.header.stamp = ros::Time::now();
  128. laser_point_cloud.header.frame_id = "base_link";
  129. this->point_cloud_pub_.publish(laser_point_cloud);
  130. }
  131. }
  132. );
  133. pub_thread.detach();
  134. }
  135. on_ = true;
  136. }
  137. bool ObstacleIdentify::isClose(common::Point pp)
  138. {
  139. for (CloseClose& cll : close_closes_) {
  140. float d = hypot(cll.x - pp.x, cll.y - pp.y);
  141. if (d < cll.close_dist) {
  142. return true;
  143. }
  144. }
  145. return false;
  146. }
  147. void ObstacleIdentify::__laserCallback(const sensor_msgs::LaserScanConstPtr& msg)
  148. {
  149. std::map<std::string, LaserParam>::iterator la_it = laser_params_.find(msg->header.frame_id);
  150. if (la_it == laser_params_.end()) {
  151. return;
  152. }
  153. LaserParam laser_config = la_it->second;
  154. std::vector<Pose2D> gather; // 数据聚类
  155. float max_detection_range = 5.f;
  156. std::map<std::string, Eigen::Matrix<float, 4, 4>>::iterator it =
  157. transforms_.find(msg->header.frame_id);
  158. if (it == transforms_.end()) {
  159. return;
  160. }
  161. Eigen::Matrix<float, 4, 4> transform = it->second;
  162. float theta = msg->angle_max;
  163. float offset = msg->angle_max + msg->angle_min;
  164. float sm_theta = 0.0;
  165. for (const float& range : msg->ranges) {
  166. theta -= msg->angle_increment;
  167. sm_theta += msg->angle_increment;
  168. if (sm_theta < (laser_config.angle_increment - 1e-10)) {
  169. continue;
  170. }
  171. else {
  172. sm_theta = 0.0;
  173. }
  174. if (range > msg->range_max) continue;
  175. if (range < msg->range_min) continue;
  176. if (range < laser_config.min_range) continue;
  177. if (range > laser_config.max_range) continue;
  178. if (theta < msg->angle_min) continue;
  179. if (theta > msg->angle_max) continue;
  180. if (range > max_detection_range) continue;
  181. if (std::isnan(range)) continue;
  182. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  183. range * sin(theta - offset),
  184. 1.0,
  185. 0.0);
  186. // //将基于传感器坐标系的数据转到基于base_link坐标系
  187. Eigen::Matrix<float, 3, 1> base_link_coord = (transform * point).head<3>();
  188. //激光转置
  189. base_link_coord = transform::Rigid3f::Rotation(Eigen::AngleAxisf(
  190. M_PI, Eigen::Vector3f::UnitX())) * base_link_coord;
  191. Pose2D base_link_point;
  192. base_link_point.x = base_link_coord(0);
  193. base_link_point.y = base_link_coord(1);
  194. if (__isIgnore(base_link_point.x, base_link_point.y, theta, laser_config.ignores)) {
  195. continue;
  196. }
  197. gather.push_back(base_link_point);
  198. }
  199. gather = __filter2D(gather, 0.05, true);
  200. __addObs(gather, msg->header.frame_id, ros::Time::now());
  201. }
  202. void ObstacleIdentify::__cameraCallback(const sensor_msgs::PointCloud2ConstPtr& msg)
  203. {
  204. std::map<std::string, CameraParam>::iterator cam_it = camera_params_.find(msg->header.frame_id);
  205. if (cam_it == camera_params_.end()) {
  206. return;
  207. }
  208. CameraParam caram_config = cam_it->second;
  209. sensor_msgs::PointCloud cloud;
  210. sensor_msgs::convertPointCloud2ToPointCloud(*msg, cloud);
  211. cloud = __extract3D(cloud, caram_config.filter_step);
  212. if (cloud.points.empty()) {
  213. return;
  214. }
  215. std::map<std::string, Eigen::Matrix<float, 4, 4>>::iterator it =
  216. transforms_.find(msg->header.frame_id);
  217. if (it == transforms_.end()) {
  218. return;
  219. }
  220. Eigen::Matrix<float, 4, 4> transform = it->second;
  221. std::vector<Pose2D> obstacle_pose;
  222. sensor_msgs::PointCloud laser_point_cloud;
  223. for(geometry_msgs::Point32& point : cloud.points) {
  224. if(std::isnan(point.x) || std::isnan(point.y) || std::isnan(point.z)) {
  225. continue;
  226. }
  227. Eigen::Matrix<float, 4, 1> pose;
  228. pose << point.z, point.x, point.y, 1.0;
  229. pose = transform * pose;
  230. if (__interval(pose(0), caram_config.x_head, caram_config.x_tail) && __interval(pose(1), caram_config.y_right, caram_config.y_left) &&
  231. __interval(pose(2), caram_config.z_ceil, caram_config.z_floor)) {
  232. Pose2D pose2d;
  233. pose2d.x = pose(0);
  234. pose2d.y = pose(1);
  235. if (__isIgnore(pose2d.x, pose2d.y, 1e10, caram_config.ignores)) {
  236. continue;
  237. }
  238. obstacle_pose.push_back(pose2d);
  239. }
  240. if (debug_3d_) {
  241. geometry_msgs::Point32 tmp;
  242. tmp.x = pose(0);
  243. tmp.y = pose(1);
  244. tmp.z = pose(2);
  245. laser_point_cloud.points.push_back(tmp);
  246. }
  247. }
  248. if (debug_3d_) {
  249. laser_point_cloud.header.stamp = ros::Time::now();
  250. laser_point_cloud.header.frame_id = "base_link";
  251. point_cloud3D_pub_.publish(laser_point_cloud);
  252. }
  253. if (!obstacle_pose.empty()) {
  254. __addObs(obstacle_pose, msg->header.frame_id, ros::Time::now());
  255. }
  256. }
  257. void ObstacleIdentify::__addObs(std::vector<Pose2D>& obs, const std::string sensor_name, ros::Time time)
  258. {
  259. mutex_.lock();
  260. Obstacle obstacle;
  261. obstacle.obstacle_pose = obs;
  262. obstacle.stamp = time;
  263. obs_[sensor_name] = obstacle;
  264. mutex_.unlock();
  265. }
  266. std::vector<Pose2D> ObstacleIdentify::__getParseObs()
  267. {
  268. mutex_.lock();
  269. std::vector<Pose2D> obstacle;
  270. for (auto& obs : obs_) {
  271. if ((ros::Time::now() - obs.second.stamp).toSec() < 0.1) {
  272. obstacle.insert(obstacle.begin(), obs.second.obstacle_pose.begin(), obs.second.obstacle_pose.end());
  273. }
  274. }
  275. obstacle = __filter2D(obstacle, 0.05, false);
  276. mutex_.unlock();
  277. return obstacle;
  278. }
  279. void ObstacleIdentify::__getPrintFoot()
  280. {
  281. std::string path = space::home() + "configure/obstacle_config.json";
  282. Json::Value c = space::readConfig(path);
  283. Json::Value copy = c;
  284. foot_.poses.clear();
  285. if (c["foot"]["x"].size() == c["foot"]["y"].size()) {
  286. for (int i = 0;i < c["foot"]["x"].size();i++) {
  287. Pose2D pose_2d;
  288. space::jsonValueTo(c["foot"]["x"][i], pose_2d.x);
  289. space::jsonValueTo(c["foot"]["y"][i], pose_2d.y);
  290. LOG(INFO)<<pose_2d.x<<" "<<pose_2d.y;
  291. foot_.poses.push_back(pose_2d);
  292. }
  293. }
  294. if (c["foot"]["x"].empty()) {
  295. c["foot"]["x"][0] = 0.0;
  296. c["foot"]["y"][0] = 0.0;
  297. if(copy != c) {
  298. space::writeConfig(path, c);
  299. }
  300. }
  301. }
  302. void ObstacleIdentify::updateFootPrint()
  303. {
  304. __getPrintFoot();
  305. }
  306. bool ObstacleIdentify::isObstacleInArea(const float& x,
  307. const float& y,
  308. const float& theta,
  309. float& distance)
  310. {
  311. std::vector<Pose2D> obstacle = __getParseObs();
  312. if (obstacle.empty() || foot_.poses.empty() || turn_off_) {
  313. return false;
  314. }
  315. Area new_foots;
  316. std::vector<Pose2D> points;
  317. if(foot_.poses.size() < 3 && !foot_.poses.empty()) {
  318. float radius = hypot(foot_.poses[0].x, foot_.poses[0].y);
  319. int num = 16;
  320. Pose2D pt;
  321. for (int i = 0; i < num; ++i) {
  322. float angle = i * 2 * M_PI / num;
  323. pt.x = cos(angle) * radius;
  324. pt.y = sin(angle) * radius;
  325. points.push_back(pt);
  326. }
  327. foot_.poses =points;
  328. }
  329. Pose2D pose;
  330. pose.x = x;
  331. pose.y = y;
  332. pose.theta = theta;
  333. for(int i = 0;i < foot_.poses.size();i++) {
  334. Pose2D foot = __localTransGlobal(foot_.poses[i], pose);
  335. new_foots.poses.push_back(foot);
  336. }
  337. debug_ = true;
  338. if (debug_) {
  339. geometry_msgs::PolygonStamped static_polygon;
  340. static_polygon.header.frame_id ="base_link";
  341. static_polygon.polygon.points.resize(new_foots.poses.size());
  342. for(int i = 0;i < foot_.poses.size();i++) {
  343. static_polygon.polygon.points[i].x =foot_.poses[i].x;
  344. static_polygon.polygon.points[i].y =foot_.poses[i].y;
  345. }
  346. static_polygon_pub_.publish(static_polygon);
  347. LOG(INFO)<<"pub foot";
  348. geometry_msgs::PolygonStamped dynamic_polygon;
  349. dynamic_polygon.header.frame_id ="base_link";
  350. dynamic_polygon.polygon.points.resize(new_foots.poses.size());
  351. for(int i=0;i<new_foots.poses.size();i++) {
  352. dynamic_polygon.polygon.points[i].x =new_foots.poses[i].x;
  353. dynamic_polygon.polygon.points[i].y =new_foots.poses[i].y;
  354. }
  355. dynamic_polygon_pub_.publish(dynamic_polygon);
  356. }
  357. for(int i = 0;i < obstacle.size();i++) {
  358. if(__poseInArea(obstacle[i], new_foots)) {
  359. distance = hypot(obstacle[i].x, obstacle[i].y);
  360. return true;
  361. }
  362. }
  363. return false;
  364. }
  365. bool ObstacleIdentify::__poseInArea(Pose2D point, Area area)
  366. {
  367. if(area.poses.empty()) {
  368. printf("Foot Error!\n");
  369. return true;
  370. }
  371. std::vector<Pose2D> points;
  372. points = area.poses;
  373. bool flag = false;
  374. float px = point.x;
  375. float py = point.y;
  376. points.push_back(points[0]);
  377. for(int i = 0;i < points.size() - 1;i++) {
  378. float x1 = points[i].x;
  379. float y1 = points[i].y;
  380. float x2 = points[i+1].x;
  381. float y2 = points[i+1].y;
  382. if((px == x1 && py == y1) || (px == x2 && py == y2)) {
  383. return true;
  384. }
  385. if((y1 < py && y2 >= py) || (y1 >= py && y2 < py)) {
  386. float x = x1 + (py - y1) * (x2 -x1) / (y2 -y1);
  387. if( x == px) {
  388. return true;
  389. }
  390. if(x > px) {
  391. flag = !flag;
  392. }
  393. }
  394. }
  395. return flag;
  396. }
  397. bool ObstacleIdentify::__isIgnore(float x, float y, float angle, std::vector<IgnoreParam> ignores)
  398. {
  399. for (IgnoreParam& param : ignores) {
  400. if (x < param.x_upper && x > param.x_lower) {
  401. return true;
  402. }
  403. if (y < param.y_upper && y > param.y_lower) {
  404. return true;
  405. }
  406. if (angle < param.angle_upper && angle > param.angle_lower) {
  407. return true;
  408. }
  409. }
  410. return false;
  411. }
  412. Pose2D ObstacleIdentify::__trasformBaseLink(Pose2D pose, const Eigen::Matrix<float, 3, 3>& transform)
  413. {
  414. const Eigen::Matrix<float, 3, 1> point(pose.x,pose.y,1.0);
  415. Eigen::Matrix<float, 3, 1> base_link_coord = transform * point;
  416. Pose2D trans_pose;
  417. trans_pose.x = base_link_coord(0);
  418. trans_pose.y = base_link_coord(1);
  419. trans_pose.theta = 0;
  420. return trans_pose;
  421. }
  422. Pose2D ObstacleIdentify::__localTransGlobal(Pose2D a, Pose2D b)
  423. {
  424. Pose2D c;
  425. c.x = b.x + a.x * cos(b.theta) - a.y * sin(b.theta);
  426. c.y = b.y + a.x * sin(b.theta) + a.y * cos(b.theta);
  427. return c;
  428. }
  429. void ObstacleIdentify::__readConfig()
  430. {
  431. std::string path = space::home() + "configure/obstacle_config.json";
  432. Json::Value c = space::readConfig(path);
  433. Json::Value copy = c;
  434. laser_params_.clear();
  435. camera_params_.clear();
  436. transforms_.clear();
  437. for (int i = 0;i < c["sensor"]["laser"].size() || i == 0;i++) {
  438. float tf_x, tf_y, tf_yaw;
  439. std::string name, topic;
  440. bool ok1 = space::jsonValueTo(c["sensor"]["laser"][i]["base"]["topic"], topic);
  441. bool ok2 = space::jsonValueTo(c["sensor"]["laser"][i]["tf"]["tf_x"], tf_x);
  442. bool ok3 = space::jsonValueTo(c["sensor"]["laser"][i]["tf"]["tf_y"], tf_y);
  443. bool ok4 = space::jsonValueTo(c["sensor"]["laser"][i]["tf"]["tf_yaw"], tf_yaw);
  444. bool ok5 = space::jsonValueTo(c["sensor"]["laser"][i]["base"]["name"], name);
  445. LaserParam laser_param;
  446. space::jsonValueTo(c["sensor"]["laser"][i]["base"]["min_range"], laser_param.min_range) ? false : laser_param.min_range = 0.0;
  447. space::jsonValueTo(c["sensor"]["laser"][i]["base"]["max_range"], laser_param.max_range) ? false : laser_param.max_range = 0.0;
  448. space::jsonValueTo(c["sensor"]["laser"][i]["base"]["angle_increment"], laser_param.angle_increment) ? false : laser_param.angle_increment = 0.0;
  449. if (ok1 && ok2 && ok3 && ok4 && ok5) {
  450. Eigen::Matrix<float, 2, 1> translation(tf_x, -tf_y);
  451. Eigen::Rotation2D<float> rotation(-tf_yaw); //yaw 轴旋转矩阵
  452. Eigen::Matrix<float, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  453. Eigen::Matrix<float, 3, 3> transform3;
  454. Eigen::Matrix<float, 4, 4> transform4;
  455. transform3 << rotation_matrix, translation, 0., 0., 1.;
  456. transform4.rightCols<1>() << 0, 0, 0, 0;
  457. transform4.block<3, 3>(0, 0, 3, 3) = transform3;
  458. transform4.bottomRows<1>() << 0, 0, 0, 0;
  459. transforms_.emplace(std::make_pair(name, transform4));
  460. subs_.push_back(nh_.subscribe(topic, 1, &ObstacleIdentify::__laserCallback, this));
  461. }
  462. else
  463. {
  464. LOG(INFO)<<"read lasr base error";
  465. }
  466. Json::Value& ignores = c["sensor"]["laser"][i]["ignore"];
  467. for (int n = 0;n < ignores.size() || n == 0;n++) {
  468. IgnoreParam ignore;
  469. space::jsonValueTo(ignores[n]["x_upper"], ignore.x_upper) ? false :
  470. (ignores[n]["x_upper"] = ignore.x_upper = 0.0);
  471. space::jsonValueTo(ignores[n]["x_lower"], ignore.x_lower) ? false :
  472. (ignores[n]["x_lower"] = ignore.x_lower = 0.0);
  473. space::jsonValueTo(ignores[n]["y_upper"], ignore.y_upper) ? false :
  474. (ignores[n]["y_upper"] = ignore.y_upper = 0.0);
  475. space::jsonValueTo(ignores[n]["y_lower"], ignore.y_lower) ? false :
  476. (ignores[n]["y_lower"] = ignore.y_lower = 0.0);
  477. space::jsonValueTo(ignores[n]["angle_upper"], ignore.angle_upper) ? false :
  478. (ignores[n]["angle_upper"] = ignore.angle_upper = 0.0);
  479. space::jsonValueTo(ignores[n]["angle_lower"], ignore.angle_lower) ? false :
  480. (ignores[n]["angle_lower"] = ignore.angle_lower = 0.0);
  481. if (ignores.size() > 0) {
  482. laser_param.ignores.push_back(ignore);
  483. }
  484. }
  485. laser_params_.emplace(std::make_pair(name, laser_param));
  486. }
  487. // for (int i = 0;i < c["sensor"]["camera"].size() || i == 0;i++) {
  488. // float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw;
  489. // std::string name, topic;
  490. // bool ok1 = space::jsonValueTo(c["sensor"]["camera"][i]["base"]["topic"], topic);
  491. // bool ok2 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_x"], tf_x);
  492. // bool ok3 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_y"], tf_y);
  493. // bool ok4 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_z"], tf_z);
  494. // bool ok5 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_roll"], tf_roll);
  495. // bool ok6 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_pitch"], tf_pitch);
  496. // bool ok7 = space::jsonValueTo(c["sensor"]["camera"][i]["tf"]["tf_yaw"], tf_yaw);
  497. // bool ok8 = space::jsonValueTo(c["sensor"]["camera"][i]["base"]["name"], name);
  498. // if (ok1 && ok2 && ok3 && ok4 && ok5 && ok6 && ok7 && ok8) {
  499. // Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(tf_roll, Eigen::Vector3d::UnitX()));
  500. // Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(tf_pitch, Eigen::Vector3d::UnitY()));
  501. // Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(tf_yaw, Eigen::Vector3d::UnitZ()));
  502. // Eigen::Matrix3f rotation_matrix;
  503. // Eigen::Matrix<float, 4, 4> transform;
  504. // rotation_matrix = (yawAngle * pitchAngle * rollAngle).cast<float>();
  505. // transform.rightCols<1>() << tf_x, tf_y, tf_z, 1.0;
  506. // transform.block<3, 3>(0, 0, 3, 3) = rotation_matrix;
  507. // transform.bottomRows<1>() << 0, 0, 0, 1.0;
  508. // transforms_.emplace(std::make_pair(name, transform));
  509. // subs_.push_back(nh_.subscribe(topic, 1, &ObstacleIdentify::__cameraCallback, this));
  510. // }
  511. // CameraParam camera_param;
  512. // Json::Value& ignores = c["sensor"]["camera"][i]["ignore"];
  513. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["z_ceil"], camera_param.z_ceil) ? false : camera_param.z_ceil = 1e10;
  514. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["z_floor"], camera_param.z_floor) ? false : camera_param.z_floor = -1e10;
  515. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["x_head"], camera_param.x_head) ? false : camera_param.x_head = 1e10;
  516. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["x_tail"], camera_param.x_tail) ? false : camera_param.x_tail = -1e10;
  517. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["y_left"], camera_param.y_left) ? false : camera_param.y_left = 1e10;
  518. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["y_right"], camera_param.y_right) ? false : camera_param.y_right = -1e10;
  519. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["pit_top"], camera_param.pit_top) ? false : camera_param.pit_top = -1e10;
  520. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["pit_bot"], camera_param.pit_bot) ? false : camera_param.pit_bot = -1e10;
  521. // space::jsonValueTo(c["sensor"]["camera"][i]["filter"]["filter_step"], camera_param.filter_step) ? false : camera_param.filter_step = 3;
  522. // for (int n = 0;n < ignores.size() || n == 0;n++) {
  523. // IgnoreParam ignore;
  524. // space::jsonValueTo(ignores[n]["x_upper"], ignore.x_upper) ? false :
  525. // (ignores[n]["x_upper"] = ignore.x_upper = 0.0);
  526. // space::jsonValueTo(ignores[n]["x_lower"], ignore.x_lower) ? false :
  527. // (ignores[n]["x_lower"] = ignore.x_lower = 0.0);
  528. // space::jsonValueTo(ignores[n]["y_upper"], ignore.y_upper) ? false :
  529. // (ignores[n]["y_upper"] = ignore.y_upper = 0.0);
  530. // space::jsonValueTo(ignores[n]["y_lower"], ignore.y_lower) ? false :
  531. // (ignores[n]["y_lower"] = ignore.y_lower = 0.0);
  532. // space::jsonValueTo(ignores[n]["angle_upper"], ignore.angle_upper) ? false :
  533. // (ignores[n]["angle_upper"] = ignore.angle_upper = 0.0);
  534. // space::jsonValueTo(ignores[n]["angle_lower"], ignore.angle_lower) ? false :
  535. // (ignores[n]["angle_lower"] = ignore.angle_lower = 0.0);
  536. // if (ignores.size() > 0) {
  537. // camera_param.ignores.push_back(ignore);
  538. // }
  539. // }
  540. // camera_params_.emplace(std::make_pair(name, camera_param));
  541. // }
  542. // for (int i = 0;i < c["close"]["close_close"].size() || i == 0;i++) {
  543. // CloseClose cc;
  544. // space::jsonValueTo(c["close"]["close_close"][i]["x"], cc.x) ? false :
  545. // (c["close"]["close_close"][i]["x"] = cc.x = 0.0);
  546. // space::jsonValueTo(c["close"]["close_close"][i]["y"], cc.y) ? false :
  547. // (c["close"]["close_close"][i]["y"] = cc.y = 0.0);
  548. // space::jsonValueTo(c["close"]["close_close"][i]["close_dist"], cc.close_dist) ? false :
  549. // (c["close"]["close_close"][i]["close_dist"] = cc.close_dist = 0.0);
  550. // if (c["close"]["close_close"].size() > 0) {
  551. // close_closes_.push_back(cc);
  552. // }
  553. // }
  554. // space::jsonValueTo(c["debug"], debug_) ? false :
  555. // (c["debug"] = debug_ = false);
  556. // space::jsonValueTo(c["debug_3d"], debug_3d_) ? false :
  557. // (c["debug_3d"] = debug_3d_ = false);
  558. // space::jsonValueTo(c["turn_off"], turn_off_) ? false :
  559. // (c["turn_off"] = turn_off_ = false);
  560. // debug_ = false;
  561. debug_3d_ = false;
  562. turn_off_ = false;
  563. if(copy != c) {
  564. space::writeConfig(path, c);
  565. }
  566. }
  567. void ObstacleIdentify::__registerLaser()
  568. {
  569. Json::Value lasers = __readLaserConfig();
  570. for (int i = 0;i < lasers.size();i++) {
  571. float tf_x, tf_y, tf_yaw;
  572. std::string name, topic;
  573. bool ok = space::jsonValueTo(lasers[i]["topic"], topic) &&
  574. space::jsonValueTo(lasers[i]["tf_x"], tf_x) &&
  575. space::jsonValueTo(lasers[i]["tf_y"], tf_y) &&
  576. space::jsonValueTo(lasers[i]["tf_yaw"], tf_yaw) &&
  577. space::jsonValueTo(lasers[i]["name"], name);
  578. if (ok) {
  579. Eigen::Matrix<float, 2, 1> translation(tf_x, -tf_y);
  580. Eigen::Rotation2D<float> rotation(-tf_yaw); //yaw 轴旋转矩阵
  581. Eigen::Matrix<float, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  582. Eigen::Matrix<float, 3, 3> transform3;
  583. Eigen::Matrix<float, 4, 4> transform4;
  584. transform3 << rotation_matrix, translation, 0., 0., 1.;
  585. transform4.rightCols<1>() << 0, 0, 0, 0;
  586. transform4.block<3, 3>(0, 0, 3, 3) = transform3;
  587. transform4.bottomRows<1>() << 0, 0, 0, 0;
  588. transforms_.emplace(std::make_pair(name, transform4));
  589. subs_.push_back(nh_.subscribe(topic, 1, &ObstacleIdentify::__laserCallback, this));
  590. }
  591. }
  592. }
  593. void ObstacleIdentify::__registerCamera()
  594. {
  595. Json::Value camera = __readCameraConfig();
  596. for (int i = 0;i < camera.size();i++) {
  597. float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw;
  598. std::string name, topic;
  599. bool ok = space::jsonValueTo(camera[i]["topic"], topic) &&
  600. space::jsonValueTo(camera[i]["tf_x"], tf_x) &&
  601. space::jsonValueTo(camera[i]["tf_y"], tf_y) &&
  602. space::jsonValueTo(camera[i]["tf_z"], tf_z) &&
  603. space::jsonValueTo(camera[i]["tf_roll"], tf_roll) &&
  604. space::jsonValueTo(camera[i]["tf_pitch"], tf_pitch) &&
  605. space::jsonValueTo(camera[i]["tf_yaw"], tf_yaw) &&
  606. space::jsonValueTo(camera[i]["name"], name);
  607. if (ok) {
  608. Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(tf_roll, Eigen::Vector3d::UnitX()));
  609. Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(tf_pitch, Eigen::Vector3d::UnitY()));
  610. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(tf_yaw, Eigen::Vector3d::UnitZ()));
  611. Eigen::Matrix3f rotation_matrix;
  612. Eigen::Matrix<float, 4, 4> transform;
  613. rotation_matrix = (yawAngle * pitchAngle * rollAngle).cast<float>();
  614. transform.rightCols<1>() << tf_x, tf_y, tf_z, 1.0;
  615. transform.block<3, 3>(0, 0, 3, 3) = rotation_matrix;
  616. transform.bottomRows<1>() << 0, 0, 0, 1.0;
  617. transforms_.emplace(std::make_pair(name, transform));
  618. subs_.push_back(nh_.subscribe(topic, 1, &ObstacleIdentify::__cameraCallback, this));
  619. }
  620. }
  621. }
  622. }