ros_node.cpp 26 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744
  1. #include <ros/ros.h>
  2. #include <tf/transform_broadcaster.h>
  3. #include <tf/transform_listener.h>
  4. #include <sensor_msgs/LaserScan.h>
  5. #include <sensor_msgs/PointCloud.h>
  6. #include <geometry_msgs/Point32.h>
  7. #include <nav_msgs/Odometry.h>
  8. #include <nav_msgs/MapMetaData.h>
  9. #include <nav_msgs/GetMap.h>
  10. #include <geometry_msgs/Pose2D.h>
  11. #include <std_msgs/Int32MultiArray.h>
  12. #include <std_msgs/Float64.h>
  13. #include <opencv2/core/core.hpp>
  14. #include <opencv2/highgui/highgui.hpp>
  15. #include "base_msgs/global_position.h"
  16. // #include "space_key/space_key.h"
  17. #include "map/map.h"
  18. #include "slam/slam.h"
  19. #include "common/common.h"
  20. #include "space_lib/space_lib.h"
  21. #include "real_match_2d/real_match_2d.h"
  22. #include "ceres_matcher/ceres_scan_matcher_2d.h"
  23. #define MAP_IDX(sx, i, j) ((sx) * (j) + (i))
  24. namespace
  25. {
  26. using namespace hlzn_slam;
  27. using namespace hlzn_slam::common;
  28. std::unique_ptr<ros::NodeHandle> nh_;
  29. ros::Publisher map_pub_, package_init_pub_, point_cloud_pub_, show_laser_pub_;
  30. /*tf相关*/
  31. std::unique_ptr<tf::TransformBroadcaster> trans_tfb_;
  32. std::unique_ptr<tf::TransformListener> tf_;
  33. ros::Duration transform_tolerance_;
  34. tf::Transform tf_transform_;
  35. std::string odom_frame_id_ = "odom";
  36. std::string base_frame_id_ = "base_link";
  37. std::string global_frame_id_ = "map";
  38. /*******/
  39. /*match*/
  40. ros::Publisher map_pose_pub_, cost_pub_;
  41. std::vector<ros::Subscriber> subs_;
  42. /*******/
  43. std::unique_ptr<slam::Slam> slam_ptr_ = nullptr;
  44. std::map<std::string, Eigen::Matrix<float, 4, 4>> transforms_;
  45. static PointCloud __transformScanData2PointCloudFilter(const sensor_msgs::LaserScanConstPtr &msg, const Eigen::Matrix<float, 4, 4> &transform,
  46. const float step_angle);
  47. static bool __getMapInfo(const std::string &map_path, const std::string &yaml_path, Eigen::MatrixXf &map,
  48. float &resolution, float &x_origin, float &y_origin);
  49. static void __locationMsgsCallback(const base_msgs::global_positionConstPtr &msg);
  50. static void __pubMapPose(const float &x, const float &y, const float &yaw);
  51. static void __pubCost(const float &cost);
  52. static void __shutDown();
  53. static void __start();
  54. static float probability_plus_;
  55. static float probability_up_;
  56. static float search_range_;
  57. static float search_angle_;
  58. static float window_size_;
  59. static float achieve_range_;
  60. static float achieve_angle_;
  61. static float submap_size_;
  62. static float submap_resolution_;
  63. static bool use_towermatch_;
  64. static bool use_odom_;
  65. static bool debug_;
  66. static float first_search_range_;
  67. static float first_search_angle_;
  68. static Json::Value __readLaserConfig()
  69. {
  70. std::string path = space::home() + "configure/laser_config.json";
  71. Json::Value c = space::readConfig(path);
  72. Json::Value laser;
  73. space::jsonValueTo(c, laser);
  74. return laser;
  75. }
  76. static bool __readLocationConfig()
  77. {
  78. std::string path = space::home() + "configure/location_config.json";
  79. Json::Value c = space::readConfig(path);
  80. Json::Value compair = c;
  81. space::jsonValueTo(c["probability_plus"], probability_plus_) ? false : (c["probability_plus"] = probability_plus_ = 0.001);
  82. space::jsonValueTo(c["probability_up"], probability_up_) ? false : (c["probability_up"] = probability_up_ = 0.2);
  83. space::jsonValueTo(c["search_range"], search_range_) ? false : (c["search_range"] = search_range_ = 0.3);
  84. space::jsonValueTo(c["search_angle"], search_angle_) ? false : (c["search_angle"] = search_angle_ = 0.1);
  85. space::jsonValueTo(c["window_size"], window_size_) ? false : (c["window_size"] = window_size_ = 20);
  86. space::jsonValueTo(c["achieve_range"], achieve_range_) ? false : (c["achieve_range"] = achieve_range_ = 0.5);
  87. space::jsonValueTo(c["achieve_angle"], achieve_angle_) ? false : (c["achieve_angle"] = achieve_angle_ = 0.4);
  88. space::jsonValueTo(c["submap_size"], submap_size_) ? false : (c["submap_size"] = submap_size_ = 15.0);
  89. space::jsonValueTo(c["submap_resolution"], submap_resolution_) ? false : (c["submap_resolution"] = submap_resolution_ = 0.05);
  90. space::jsonValueTo(c["use_towermatch"], use_towermatch_) ? false : (c["use_towermatch"] = use_towermatch_ = true);
  91. space::jsonValueTo(c["use_odom"], use_odom_) ? false : (c["use_odom"] = use_odom_ = true);
  92. space::jsonValueTo(c["debug"], debug_) ? false : (c["debug"] = debug_ = false);
  93. LOG(INFO) << use_odom_;
  94. space::jsonValueTo(c["first_search_range"], first_search_range_) ? false : (c["first_search_range"] = first_search_range_ = 5.0);
  95. space::jsonValueTo(c["first_search_angle"], first_search_angle_) ? false : (c["first_search_angle"] = first_search_angle_ = M_PI);
  96. if (compair != c)
  97. {
  98. space::writeConfig(path, c);
  99. }
  100. return true;
  101. }
  102. static bool __CacluLaserToBaseLinkTransform()
  103. {
  104. transforms_.clear();
  105. Json::Value lasers = __readLaserConfig();
  106. for (int i = 0; i < lasers.size(); i++)
  107. {
  108. float tf_x, tf_y, tf_z, tf_roll, tf_pitch, tf_yaw;
  109. std::string name;
  110. bool ok = space::jsonValueTo(lasers[i]["tf_x"], tf_x) &&
  111. space::jsonValueTo(lasers[i]["tf_y"], tf_y) &&
  112. space::jsonValueTo(lasers[i]["tf_z"], tf_z) &&
  113. space::jsonValueTo(lasers[i]["tf_roll"], tf_roll) &&
  114. space::jsonValueTo(lasers[i]["tf_pitch"], tf_pitch) &&
  115. space::jsonValueTo(lasers[i]["tf_yaw"], tf_yaw) &&
  116. space::jsonValueTo(lasers[i]["name"], name);
  117. if (ok)
  118. {
  119. Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(tf_roll, Eigen::Vector3d::UnitX()));
  120. Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(tf_pitch, Eigen::Vector3d::UnitY()));
  121. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(tf_yaw, Eigen::Vector3d::UnitZ()));
  122. Eigen::Matrix3f rotation_matrix;
  123. Eigen::Matrix<float, 4, 4> transform;
  124. rotation_matrix = (yawAngle * pitchAngle * rollAngle).cast<float>();
  125. transform.rightCols<1>() << tf_x, tf_y, tf_z, 1.0;
  126. transform.block<3, 3>(0, 0, 3, 3) = rotation_matrix;
  127. transform.bottomRows<1>() << 0, 0, 0, 1.0;
  128. transforms_.emplace(std::make_pair(name, transform));
  129. }
  130. }
  131. if (!transforms_.empty())
  132. {
  133. return true;
  134. }
  135. return false;
  136. }
  137. static void __mapPub(std::string map_file, std::string config_path)
  138. {
  139. static nav_msgs::GetMap::Response map_res;
  140. cv::Mat image;
  141. float x_origin, y_origin, resolution, occupied_thresh, free_thresh;
  142. image = cv::imread(map_file, cv::IMREAD_GRAYSCALE);
  143. tf::Quaternion q;
  144. q.setRPY(0, 0, 0);
  145. Json::Value c = space::readConfig(config_path);
  146. bool ok = space::jsonValueTo(c["x_origin"], x_origin) &&
  147. space::jsonValueTo(c["y_origin"], y_origin) &&
  148. space::jsonValueTo(c["resolution"], resolution) &&
  149. space::jsonValueTo(c["occupied_thresh"], occupied_thresh) &&
  150. space::jsonValueTo(c["free_thresh"], free_thresh);
  151. map_res.map.info.map_load_time = ros::Time::now();
  152. map_res.map.header.frame_id = "map";
  153. map_res.map.header.stamp = ros::Time::now();
  154. map_res.map.info.width = image.cols;
  155. map_res.map.info.height = image.rows;
  156. map_res.map.info.resolution = resolution;
  157. map_res.map.info.origin.position.x = -x_origin;
  158. map_res.map.info.origin.position.y = -y_origin;
  159. map_res.map.info.origin.position.z = 0.0;
  160. map_res.map.info.origin.orientation.x = q.x();
  161. map_res.map.info.origin.orientation.y = q.y();
  162. map_res.map.info.origin.orientation.z = q.z();
  163. map_res.map.info.origin.orientation.w = q.w();
  164. map_res.map.data.resize(map_res.map.info.width * map_res.map.info.height);
  165. unsigned char *p;
  166. unsigned char value;
  167. unsigned char pix = 0;
  168. for (size_t x = 0; x < image.rows; ++x)
  169. {
  170. p = image.ptr<uchar>(x);
  171. for (size_t y = 0; y < image.cols; ++y)
  172. {
  173. pix = *(p + y);
  174. float cm = float(pix) / 255.f;
  175. if (cm < 1 - occupied_thresh)
  176. {
  177. value = (1 - cm) * 255;
  178. }
  179. else if (cm > 1 - free_thresh)
  180. {
  181. value = 0;
  182. }
  183. else
  184. {
  185. value = 0;
  186. }
  187. map_res.map.data[MAP_IDX(map_res.map.info.width, y, map_res.map.info.height - x - 1)] = value;
  188. }
  189. }
  190. LOG(INFO) << "Read a " << map_res.map.info.width << " * " << map_res.map.info.height
  191. << " @ " << map_res.map.info.resolution << " Map!";
  192. map_pub_.publish(map_res.map);
  193. }
  194. static PointCloud __transformScanData2PointCloud(const sensor_msgs::LaserScanConstPtr &msg, const Eigen::Matrix<float, 4, 4> &transform)
  195. {
  196. PointCloud point_cloud;
  197. float theta = msg->angle_max;
  198. float offset = msg->angle_max + msg->angle_min;
  199. for (const float &range : msg->ranges)
  200. {
  201. theta -= msg->angle_increment;
  202. if (range > msg->range_max)
  203. continue;
  204. if (range < msg->range_min)
  205. continue;
  206. if (theta < msg->angle_min)
  207. continue;
  208. if (theta > msg->angle_max)
  209. continue;
  210. if (std::isnan(range))
  211. continue;
  212. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  213. -range * sin(theta - offset),
  214. 0.0,
  215. 1.0);
  216. // 将基于传感器坐标系的数据转到基于base_link坐标系
  217. Eigen::Matrix<float, 4, 1> base = transform * point;
  218. point_cloud.data.push_back(
  219. Eigen::Vector3f(base(0), base(1), base(2)));
  220. }
  221. point_cloud.time = std::chrono::system_clock::now();
  222. return point_cloud;
  223. }
  224. static common::laserScan __transformROSScanData2CommonScan(const sensor_msgs::LaserScanConstPtr &msg)
  225. {
  226. laserScan scan;
  227. scan.angle_max = msg->angle_max;
  228. scan.angle_min = msg->angle_min;
  229. scan.range_max = msg->range_max;
  230. scan.range_min = msg->range_min;
  231. scan.ranges = msg->ranges;
  232. scan.angle_increment = msg->angle_increment;
  233. return scan;
  234. }
  235. static PointCloud __transformScanData2PointCloudFilter(const sensor_msgs::LaserScanConstPtr &msg, const Eigen::Matrix<float, 4, 4> &transform)
  236. {
  237. static sensor_msgs::LaserScan last_msg = *msg;
  238. PointCloud point_cloud;
  239. float theta = msg->angle_max;
  240. float offset = msg->angle_max + msg->angle_min;
  241. for (int i = 0; i < msg->ranges.size(); i++)
  242. {
  243. float range = msg->ranges[i];
  244. float range_last = last_msg.ranges[i];
  245. theta -= msg->angle_increment;
  246. if (range > msg->range_max)
  247. continue;
  248. if (range < msg->range_min)
  249. continue;
  250. if (theta < msg->angle_min)
  251. continue;
  252. if (theta > msg->angle_max)
  253. continue;
  254. if (std::isnan(range))
  255. continue;
  256. if (std::isnan(range_last))
  257. {
  258. float dist = hypot((range_last - range) * cos(theta - offset),
  259. (range_last - range) * sin(theta - offset));
  260. float max = (msg->header.stamp - last_msg.header.stamp).toSec() * 0.75;
  261. if (dist > max)
  262. {
  263. continue;
  264. }
  265. }
  266. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  267. -range * sin(theta - offset),
  268. 0.0,
  269. 1.0);
  270. // 将基于传感器坐标系的数据转到基于base_link坐标系
  271. Eigen::Matrix<float, 4, 1> base = transform * point;
  272. point_cloud.data.push_back(
  273. Eigen::Vector3f(base(0), base(1), base(2)));
  274. }
  275. point_cloud.time = std::chrono::system_clock::now();
  276. last_msg = *msg;
  277. return point_cloud;
  278. }
  279. static PointCloud __transformScanData2PointCloudFilter(const sensor_msgs::LaserScanConstPtr &msg, const Eigen::Matrix<float, 4, 4> &transform, const float step_angle)
  280. {
  281. PointCloud point_cloud;
  282. float theta = msg->angle_max;
  283. float offset = msg->angle_max + msg->angle_min;
  284. float step = 0;
  285. for (int i = 0; i < msg->ranges.size(); i++)
  286. {
  287. float range = msg->ranges[i];
  288. theta -= msg->angle_increment;
  289. step += msg->angle_increment;
  290. if (step < step_angle)
  291. continue;
  292. if (range > msg->range_max)
  293. continue;
  294. if (range < msg->range_min)
  295. continue;
  296. if (theta < msg->angle_min)
  297. continue;
  298. if (theta > msg->angle_max)
  299. continue;
  300. if (std::isnan(range))
  301. continue;
  302. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  303. -range * sin(theta - offset),
  304. 0.0,
  305. 1.0);
  306. // 将基于传感器坐标系的数据转到基于base_link坐标系
  307. Eigen::Matrix<float, 4, 1> base = transform * point;
  308. point_cloud.data.push_back(
  309. Eigen::Vector3f(base(0), base(1), base(2)));
  310. step = 0;
  311. }
  312. point_cloud.time = std::chrono::system_clock::now();
  313. return point_cloud;
  314. }
  315. static void __tfMapToOdom(const float &x, const float &y, const float &yaw, ros::Time stamp)
  316. {
  317. tf::Stamped<tf::Pose> odom_to_map;
  318. ros::Time copy_stamp = stamp;
  319. transform_tolerance_.fromSec(0.03);
  320. try
  321. {
  322. /*tmp_tf,从map原点看base_link的位置*/
  323. tf::Transform tmp_tf(tf::createQuaternionFromYaw(yaw),
  324. tf::Vector3(x, y, 0.0));
  325. }
  326. catch (tf::TransformException)
  327. {
  328. // LOG(INFO)<<"Location Failed to subtract base to odom transform";
  329. return;
  330. }
  331. tf_transform_ = tf::Transform(tf::createQuaternionFromYaw(yaw), tf::Vector3(x, y, 0.0));
  332. ros::Time transform_expiration = (copy_stamp + transform_tolerance_);
  333. /*发布tf转换关系,latest_tf_.inverse() 得到的是从map原点看odom原点的位置,也就是 odom->map的转换关系*/
  334. tf::StampedTransform tmp_tf_stamped(tf_transform_.inverse(),
  335. transform_expiration,
  336. base_frame_id_, global_frame_id_);
  337. trans_tfb_->sendTransform(tmp_tf_stamped);
  338. }
  339. common::PointCloud __transformPointCloud(
  340. const common::PointCloud &point_cloud, const common::Rigid2f &transform)
  341. {
  342. common::PointCloud trans_cloud;
  343. trans_cloud.data.resize(point_cloud.data.size());
  344. for (int i = 0; i < point_cloud.data.size(); i++)
  345. {
  346. Eigen::Vector3f trans;
  347. common::Rigid2f::Vector vector = point_cloud.data[i].head<2>();
  348. vector = transform * vector;
  349. trans = Eigen::Vector3f(vector(0), vector(1), 0.0);
  350. trans_cloud.data[i] = trans;
  351. }
  352. trans_cloud.time = point_cloud.time;
  353. return trans_cloud;
  354. }
  355. static void __laserDataCallback(const sensor_msgs::LaserScanConstPtr &msg)
  356. {
  357. // ROS_WARN("space_slam: __laserDataCallback() get in !!");
  358. if (slam_ptr_ == nullptr)
  359. {
  360. return;
  361. }
  362. std::map<std::string, Eigen::Matrix<float, 4, 4>>::iterator it =
  363. transforms_.find(msg->header.frame_id);
  364. if (it == transforms_.end())
  365. {
  366. return;
  367. }
  368. common::PointCloud point_cloud = __transformScanData2PointCloud(msg, it->second);
  369. common::laserScan scan = __transformROSScanData2CommonScan(msg);
  370. slam_ptr_->addPointCloud(point_cloud, scan, it->second);
  371. if (debug_)
  372. {
  373. sensor_msgs::PointCloud laser_point_cloud;
  374. for (const Eigen::Vector3f &point : point_cloud.data)
  375. {
  376. geometry_msgs::Point32 tmp;
  377. tmp.x = point(0);
  378. tmp.y = point(1);
  379. tmp.z = 0;
  380. laser_point_cloud.points.push_back(tmp);
  381. }
  382. laser_point_cloud.header.stamp = ros::Time::now();
  383. laser_point_cloud.header.frame_id = "base_link";
  384. point_cloud_pub_.publish(laser_point_cloud);
  385. }
  386. common::TimeRigid2f time_pose = slam_ptr_->getCurrentPose();
  387. std::chrono::duration<float> dur = std::chrono::system_clock::now() - time_pose.stamp;
  388. if (dur.count() < 0.1)
  389. { // 100ms
  390. __pubMapPose(time_pose.pose.translation()(0), time_pose.pose.translation()(1),
  391. time_pose.pose.rotation().angle());
  392. __tfMapToOdom(time_pose.pose.translation()(0), time_pose.pose.translation()(1),
  393. time_pose.pose.rotation().angle(), msg->header.stamp);
  394. __pubCost(time_pose.cost);
  395. }
  396. { // show cloud
  397. PointCloud show_cloud = __transformScanData2PointCloudFilter(msg, it->second, 0.017);
  398. sensor_msgs::PointCloud show_cloud_ros;
  399. show_cloud = __transformPointCloud(show_cloud, time_pose.pose);
  400. for (const Eigen::Vector3f &point : show_cloud.data)
  401. {
  402. geometry_msgs::Point32 tmp;
  403. tmp.x = point(0);
  404. tmp.y = point(1);
  405. tmp.z = 0;
  406. show_cloud_ros.points.push_back(tmp);
  407. }
  408. show_cloud_ros.header.stamp = ros::Time::now();
  409. show_cloud_ros.header.frame_id = "map";
  410. show_laser_pub_.publish(show_cloud_ros);
  411. }
  412. }
  413. static void __odomDataCallback(const nav_msgs::OdometryConstPtr &msg)
  414. {
  415. if (slam_ptr_ != nullptr)
  416. {
  417. float x = msg->pose.pose.position.x;
  418. float y = msg->pose.pose.position.y;
  419. float yaw = tf::getYaw(msg->pose.pose.orientation);
  420. float vx = msg->twist.twist.linear.x;
  421. float angular = msg->twist.twist.angular.z;
  422. slam_ptr_->addOdom2DVelocity(vx, angular);
  423. slam_ptr_->addOdom2D(x, y, yaw);
  424. }
  425. }
  426. static void __locationMsgsCallback(const base_msgs::global_positionConstPtr &msg)
  427. {
  428. enum LOCMODE
  429. {
  430. QUIT = 0,
  431. FAST,
  432. EXACT,
  433. CALIBRATION
  434. };
  435. bool fast_init = false;
  436. __shutDown();
  437. if (msg->mode == QUIT)
  438. {
  439. return;
  440. }
  441. else if (msg->mode == FAST)
  442. {
  443. fast_init = true;
  444. }
  445. else
  446. {
  447. fast_init = false;
  448. }
  449. Eigen::MatrixXf map;
  450. float resolution, x_origin, y_origin;
  451. std::string map_path = msg->map_path + ".png";
  452. std::string yaml_path = msg->yaml_path + ".json";
  453. __readLocationConfig();
  454. __mapPub(map_path, yaml_path);
  455. if (__getMapInfo(map_path, yaml_path, map, resolution, x_origin, y_origin))
  456. {
  457. std::unique_ptr<hlzn_slam::Map> global_map =
  458. std::unique_ptr<hlzn_slam::Map>(
  459. new Map(map, resolution, x_origin, y_origin));
  460. slam_ptr_ = std::unique_ptr<slam::Slam>(
  461. new slam::Slam(std::move(global_map)));
  462. slam_ptr_->setParam(search_range_,
  463. search_angle_,
  464. use_towermatch_,
  465. probability_plus_,
  466. probability_up_,
  467. window_size_,
  468. achieve_range_,
  469. achieve_angle_,
  470. submap_size_,
  471. submap_resolution_,
  472. use_odom_);
  473. slam_ptr_->init(common::Rigid2f(
  474. {msg->init_position.pose.position.x, msg->init_position.pose.position.y},
  475. tf::getYaw(msg->init_position.pose.orientation)),
  476. fast_init, first_search_range_, first_search_angle_);
  477. }
  478. else
  479. {
  480. LOG(INFO) << "[LOCATION]: read map error!";
  481. return;
  482. }
  483. __start();
  484. }
  485. static void __pubMapPose(const float &x, const float &y, const float &yaw)
  486. {
  487. geometry_msgs::Pose2D map_pose;
  488. map_pose.x = x;
  489. map_pose.y = y;
  490. map_pose.theta = yaw;
  491. map_pose_pub_.publish(map_pose);
  492. }
  493. static void __pubCost(const float &cost)
  494. {
  495. std_msgs::Float64 cost_data;
  496. cost_data.data = cost;
  497. cost_pub_.publish(cost_data);
  498. }
  499. static bool __ReadMapInfo(const std::string &path,
  500. float &resolution, float &x_origin, float &y_origin, float &occupied_thresh, float &free_thresh)
  501. {
  502. Json::Value c = space::readConfig(path);
  503. bool ok = space::jsonValueTo(c["x_origin"], x_origin) &&
  504. space::jsonValueTo(c["y_origin"], y_origin) &&
  505. space::jsonValueTo(c["resolution"], resolution) &&
  506. space::jsonValueTo(c["occupied_thresh"], occupied_thresh) &&
  507. space::jsonValueTo(c["free_thresh"], free_thresh);
  508. if (ok)
  509. {
  510. return true;
  511. }
  512. return false;
  513. }
  514. static bool __getMapInfo(const std::string &map_path, const std::string &yaml_path, Eigen::MatrixXf &map,
  515. float &resolution, float &x_origin, float &y_origin)
  516. {
  517. float occupied_thresh, free_thresh;
  518. if (!__ReadMapInfo(yaml_path, resolution, x_origin, y_origin, occupied_thresh, free_thresh))
  519. {
  520. return false;
  521. }
  522. cv::Mat image;
  523. image = cv::imread(map_path, cv::IMREAD_GRAYSCALE);
  524. unsigned char *p;
  525. unsigned char pix = 0;
  526. map.setZero(image.rows, image.cols);
  527. for (size_t x = 0; x < image.rows; ++x)
  528. {
  529. p = image.ptr<uchar>(x);
  530. for (size_t y = 0; y < image.cols; ++y)
  531. {
  532. pix = *(p + y);
  533. float cm = float(pix) / 255.f;
  534. if (cm < 1 - occupied_thresh)
  535. {
  536. map(x, y) = 1 - cm;
  537. }
  538. else if (cm > 1 - free_thresh)
  539. {
  540. map(x, y) = 0;
  541. }
  542. else
  543. {
  544. map(x, y) = 0;
  545. }
  546. }
  547. }
  548. return true;
  549. }
  550. void match()
  551. {
  552. }
  553. static void __shutDown()
  554. {
  555. for (ros::Subscriber &sub : subs_)
  556. {
  557. sub.shutdown();
  558. }
  559. subs_.clear();
  560. std_msgs::Int32MultiArray msg;
  561. msg.data.push_back(2);
  562. msg.data.push_back(0);
  563. package_init_pub_.publish(msg);
  564. }
  565. static void __start()
  566. {
  567. Json::Value lasers = __readLaserConfig();
  568. __shutDown();
  569. __CacluLaserToBaseLinkTransform();
  570. map_pose_pub_ = nh_->advertise<geometry_msgs::Pose2D>("map_pose", 1);
  571. subs_.push_back(nh_->subscribe<nav_msgs::Odometry>("odom", 1, &__odomDataCallback));
  572. ROS_WARN("laser.size() = %d", lasers.size());
  573. for (int i = 0; i < lasers.size(); i++)
  574. {
  575. std::string topic = "";
  576. if (space::jsonValueTo(lasers[i]["topic"], topic))
  577. {
  578. subs_.push_back(nh_->subscribe<sensor_msgs::LaserScan>(topic, 1, &__laserDataCallback));
  579. ROS_WARN("Topic: %s", topic.c_str());
  580. }
  581. }
  582. LOG(INFO) << "[LOCATION] start ok! 11111";
  583. std_msgs::Int32MultiArray msg;
  584. msg.data.push_back(2); // = 2;
  585. msg.data.push_back(1);
  586. package_init_pub_.publish(msg);
  587. }
  588. }
  589. int main(int argc, char **argv)
  590. {
  591. static ros::Subscriber sub;
  592. ros::init(argc, argv, "space_location_node");
  593. ROS_WARN(" GET IN space_slam ros_node !!");
  594. // if(space::key::chk()) {
  595. // LOG(WARNING) << "推荐使用正版软件";
  596. // space::key::rt(86400);
  597. // return 0;
  598. // }
  599. trans_tfb_ = std::unique_ptr<tf::TransformBroadcaster>(new tf::TransformBroadcaster());
  600. tf_ = std::unique_ptr<tf::TransformListener>(new tf::TransformListener());
  601. nh_ = std::unique_ptr<ros::NodeHandle>(new ros::NodeHandle());
  602. // 用激光数据激活定位包
  603. map_pub_ = nh_->advertise<nav_msgs::OccupancyGrid>("map", 1, true);
  604. package_init_pub_ = nh_->advertise<std_msgs::Int32MultiArray>("/package_init", 1, true);
  605. point_cloud_pub_ = nh_->advertise<sensor_msgs::PointCloud>("/point_cloud", 1);
  606. show_laser_pub_ = nh_->advertise<sensor_msgs::PointCloud>("/show_laser", 1);
  607. cost_pub_ = nh_->advertise<std_msgs::Float64>("/location_cost", 1);
  608. sub = nh_->subscribe<base_msgs::global_position>("location_msgs", 1, &__locationMsgsCallback);
  609. ros::spin();
  610. return 1;
  611. }