hdl_graph_slam_nodelet.cpp 41 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677787980818283848586878889909192939495969798991001011021031041051061071081091101111121131141151161171181191201211221231241251261271281291301311321331341351361371381391401411421431441451461471481491501511521531541551561571581591601611621631641651661671681691701711721731741751761771781791801811821831841851861871881891901911921931941951961971981992002012022032042052062072082092102112122132142152162172182192202212222232242252262272282292302312322332342352362372382392402412422432442452462472482492502512522532542552562572582592602612622632642652662672682692702712722732742752762772782792802812822832842852862872882892902912922932942952962972982993003013023033043053063073083093103113123133143153163173183193203213223233243253263273283293303313323333343353363373383393403413423433443453463473483493503513523533543553563573583593603613623633643653663673683693703713723733743753763773783793803813823833843853863873883893903913923933943953963973983994004014024034044054064074084094104114124134144154164174184194204214224234244254264274284294304314324334344354364374384394404414424434444454464474484494504514524534544554564574584594604614624634644654664674684694704714724734744754764774784794804814824834844854864874884894904914924934944954964974984995005015025035045055065075085095105115125135145155165175185195205215225235245255265275285295305315325335345355365375385395405415425435445455465475485495505515525535545555565575585595605615625635645655665675685695705715725735745755765775785795805815825835845855865875885895905915925935945955965975985996006016026036046056066076086096106116126136146156166176186196206216226236246256266276286296306316326336346356366376386396406416426436446456466476486496506516526536546556566576586596606616626636646656666676686696706716726736746756766776786796806816826836846856866876886896906916926936946956966976986997007017027037047057067077087097107117127137147157167177187197207217227237247257267277287297307317327337347357367377387397407417427437447457467477487497507517527537547557567577587597607617627637647657667677687697707717727737747757767777787797807817827837847857867877887897907917927937947957967977987998008018028038048058068078088098108118128138148158168178188198208218228238248258268278288298308318328338348358368378388398408418428438448458468478488498508518528538548558568578588598608618628638648658668678688698708718728738748758768778788798808818828838848858868878888898908918928938948958968978988999009019029039049059069079089099109119129139149159169179189199209219229239249259269279289299309319329339349359369379389399409419429439449459469479489499509519529539549559569579589599609619629639649659669679689699709719729739749759769779789799809819829839849859869879889899909919929939949959969979989991000100110021003100410051006100710081009101010111012101310141015101610171018101910201021102210231024102510261027102810291030103110321033103410351036103710381039104010411042104310441045104610471048104910501051105210531054105510561057105810591060106110621063106410651066106710681069107010711072107310741075107610771078107910801081108210831084108510861087108810891090109110921093109410951096109710981099110011011102110311041105110611071108110911101111
  1. // SPDX-License-Identifier: BSD-2-Clause
  2. #include <ctime>
  3. #include <mutex>
  4. #include <atomic>
  5. #include <memory>
  6. #include <iomanip>
  7. #include <iostream>
  8. #include <unordered_map>
  9. #include <boost/format.hpp>
  10. #include <boost/thread.hpp>
  11. #include <boost/filesystem.hpp>
  12. #include <boost/algorithm/string.hpp>
  13. #include <Eigen/Dense>
  14. #include <pcl/io/pcd_io.h>
  15. #include <ros/ros.h>
  16. #include <geodesy/utm.h>
  17. #include <geodesy/wgs84.h>
  18. #include <pcl_ros/point_cloud.h>
  19. #include <message_filters/subscriber.h>
  20. #include <message_filters/time_synchronizer.h>
  21. #include <message_filters/sync_policies/approximate_time.h>
  22. #include <tf_conversions/tf_eigen.h>
  23. #include <tf/transform_listener.h>
  24. #include <std_msgs/Time.h>
  25. #include <nav_msgs/Odometry.h>
  26. #include <nmea_msgs/Sentence.h>
  27. #include <sensor_msgs/Imu.h>
  28. #include <sensor_msgs/NavSatFix.h>
  29. #include <sensor_msgs/PointCloud2.h>
  30. #include <geographic_msgs/GeoPointStamped.h>
  31. #include <visualization_msgs/MarkerArray.h>
  32. #include <hdl_graph_slam/FloorCoeffs.h>
  33. #include <hdl_graph_slam/SaveMap.h>
  34. #include <hdl_graph_slam/LoadGraph.h>
  35. #include <hdl_graph_slam/DumpGraph.h>
  36. #include <nodelet/nodelet.h>
  37. #include <pluginlib/class_list_macros.h>
  38. #include <hdl_graph_slam/ros_utils.hpp>
  39. #include <hdl_graph_slam/ros_time_hash.hpp>
  40. #include <hdl_graph_slam/graph_slam.hpp>
  41. #include <hdl_graph_slam/keyframe.hpp>
  42. #include <hdl_graph_slam/keyframe_updater.hpp>
  43. #include <hdl_graph_slam/loop_detector.hpp>
  44. #include <hdl_graph_slam/information_matrix_calculator.hpp>
  45. #include <hdl_graph_slam/map_cloud_generator.hpp>
  46. #include <hdl_graph_slam/nmea_sentence_parser.hpp>
  47. #include <g2o/types/slam3d/edge_se3.h>
  48. #include <g2o/types/slam3d/vertex_se3.h>
  49. #include <g2o/edge_se3_plane.hpp>
  50. #include <g2o/edge_se3_priorxy.hpp>
  51. #include <g2o/edge_se3_priorxyz.hpp>
  52. #include <g2o/edge_se3_priorvec.hpp>
  53. #include <g2o/edge_se3_priorquat.hpp>
  54. namespace hdl_graph_slam {
  55. class HdlGraphSlamNodelet : public nodelet::Nodelet {
  56. public:
  57. typedef pcl::PointXYZI PointT;
  58. typedef message_filters::sync_policies::ApproximateTime<nav_msgs::Odometry, sensor_msgs::PointCloud2> ApproxSyncPolicy;
  59. HdlGraphSlamNodelet() {}
  60. virtual ~HdlGraphSlamNodelet() {}
  61. virtual void onInit() {
  62. nh = getNodeHandle();
  63. mt_nh = getMTNodeHandle();
  64. private_nh = getPrivateNodeHandle();
  65. // init parameters
  66. published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/odom");
  67. map_frame_id = private_nh.param<std::string>("map_frame_id", "map");
  68. odom_frame_id = private_nh.param<std::string>("odom_frame_id", "odom");
  69. map_cloud_resolution = private_nh.param<double>("map_cloud_resolution", 0.05);
  70. trans_odom2map.setIdentity();
  71. max_keyframes_per_update = private_nh.param<int>("max_keyframes_per_update", 10);
  72. //
  73. anchor_node = nullptr;
  74. anchor_edge = nullptr;
  75. floor_plane_node = nullptr;
  76. graph_slam.reset(new GraphSLAM(private_nh.param<std::string>("g2o_solver_type", "lm_var")));
  77. keyframe_updater.reset(new KeyframeUpdater(private_nh));
  78. loop_detector.reset(new LoopDetector(private_nh));
  79. map_cloud_generator.reset(new MapCloudGenerator());
  80. inf_calclator.reset(new InformationMatrixCalculator(private_nh));
  81. nmea_parser.reset(new NmeaSentenceParser());
  82. gps_time_offset = private_nh.param<double>("gps_time_offset", 0.0);
  83. gps_edge_stddev_xy = private_nh.param<double>("gps_edge_stddev_xy", 10000.0);
  84. gps_edge_stddev_z = private_nh.param<double>("gps_edge_stddev_z", 10.0);
  85. floor_edge_stddev = private_nh.param<double>("floor_edge_stddev", 10.0);
  86. imu_time_offset = private_nh.param<double>("imu_time_offset", 0.0);
  87. enable_imu_orientation = private_nh.param<bool>("enable_imu_orientation", false);
  88. enable_imu_acceleration = private_nh.param<bool>("enable_imu_acceleration", false);
  89. imu_orientation_edge_stddev = private_nh.param<double>("imu_orientation_edge_stddev", 0.1);
  90. imu_acceleration_edge_stddev = private_nh.param<double>("imu_acceleration_edge_stddev", 3.0);
  91. points_topic = private_nh.param<std::string>("points_topic", "/velodyne_points");
  92. // subscribers
  93. odom_sub.reset(new message_filters::Subscriber<nav_msgs::Odometry>(mt_nh, published_odom_topic, 256));
  94. cloud_sub.reset(new message_filters::Subscriber<sensor_msgs::PointCloud2>(mt_nh, "/filtered_points", 32));
  95. sync.reset(new message_filters::Synchronizer<ApproxSyncPolicy>(ApproxSyncPolicy(32), *odom_sub, *cloud_sub));
  96. sync->registerCallback(boost::bind(&HdlGraphSlamNodelet::cloud_callback, this, _1, _2));
  97. imu_sub = nh.subscribe("/gpsimu_driver/imu_data", 1024, &HdlGraphSlamNodelet::imu_callback, this);
  98. floor_sub = nh.subscribe("/floor_detection/floor_coeffs", 1024, &HdlGraphSlamNodelet::floor_coeffs_callback, this);
  99. if(private_nh.param<bool>("enable_gps", true)) {
  100. gps_sub = mt_nh.subscribe("/gps/geopoint", 1024, &HdlGraphSlamNodelet::gps_callback, this);
  101. nmea_sub = mt_nh.subscribe("/gpsimu_driver/nmea_sentence", 1024, &HdlGraphSlamNodelet::nmea_callback, this);
  102. navsat_sub = mt_nh.subscribe("/gps/navsat", 1024, &HdlGraphSlamNodelet::navsat_callback, this);
  103. }
  104. // publishers
  105. markers_pub = mt_nh.advertise<visualization_msgs::MarkerArray>("/hdl_graph_slam/markers", 16);
  106. odom2map_pub = mt_nh.advertise<geometry_msgs::TransformStamped>("/hdl_graph_slam/odom2pub", 16);
  107. map_points_pub = mt_nh.advertise<sensor_msgs::PointCloud2>("/hdl_graph_slam/map_points", 1, true);
  108. read_until_pub = mt_nh.advertise<std_msgs::Header>("/hdl_graph_slam/read_until", 32);
  109. load_service_server = mt_nh.advertiseService("/hdl_graph_slam/load", &HdlGraphSlamNodelet::load_service, this);
  110. dump_service_server = mt_nh.advertiseService("/hdl_graph_slam/dump", &HdlGraphSlamNodelet::dump_service, this);
  111. save_map_service_server = mt_nh.advertiseService("/hdl_graph_slam/save_map", &HdlGraphSlamNodelet::save_map_service, this);
  112. graph_updated = false;
  113. double graph_update_interval = private_nh.param<double>("graph_update_interval", 3.0);
  114. double map_cloud_update_interval = private_nh.param<double>("map_cloud_update_interval", 10.0);
  115. optimization_timer = mt_nh.createWallTimer(ros::WallDuration(graph_update_interval), &HdlGraphSlamNodelet::optimization_timer_callback, this);
  116. map_publish_timer = mt_nh.createWallTimer(ros::WallDuration(map_cloud_update_interval), &HdlGraphSlamNodelet::map_points_publish_timer_callback, this);
  117. }
  118. private:
  119. /**
  120. * @brief received point clouds are pushed to #keyframe_queue
  121. * @param odom_msg
  122. * @param cloud_msg
  123. */
  124. void cloud_callback(const nav_msgs::OdometryConstPtr& odom_msg, const sensor_msgs::PointCloud2::ConstPtr& cloud_msg) {
  125. const ros::Time& stamp = cloud_msg->header.stamp;
  126. Eigen::Isometry3d odom = odom2isometry(odom_msg);
  127. pcl::PointCloud<PointT>::Ptr cloud(new pcl::PointCloud<PointT>());
  128. pcl::fromROSMsg(*cloud_msg, *cloud);
  129. if(base_frame_id.empty()) {
  130. base_frame_id = cloud_msg->header.frame_id;
  131. }
  132. if(!keyframe_updater->update(odom)) {
  133. std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
  134. if(keyframe_queue.empty()) {
  135. std_msgs::Header read_until;
  136. read_until.stamp = stamp + ros::Duration(10, 0);
  137. read_until.frame_id = points_topic;
  138. read_until_pub.publish(read_until);
  139. read_until.frame_id = "/filtered_points";
  140. read_until_pub.publish(read_until);
  141. }
  142. return;
  143. }
  144. double accum_d = keyframe_updater->get_accum_distance();
  145. KeyFrame::Ptr keyframe(new KeyFrame(stamp, odom, accum_d, cloud));
  146. std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
  147. keyframe_queue.push_back(keyframe);
  148. }
  149. /**
  150. * @brief this method adds all the keyframes in #keyframe_queue to the pose graph (odometry edges)
  151. * @return if true, at least one keyframe was added to the pose graph
  152. * 将队列中的关键帧添加到位姿图中,并返回是否至少有一个关键帧被添加
  153. */
  154. bool flush_keyframe_queue() {
  155. std::lock_guard<std::mutex> lock(keyframe_queue_mutex);
  156. if(keyframe_queue.empty()) {
  157. return false;
  158. }
  159. trans_odom2map_mutex.lock();
  160. Eigen::Isometry3d odom2map(trans_odom2map.cast<double>());
  161. trans_odom2map_mutex.unlock();
  162. std::cout << "flush_keyframe_queue - keyframes len:"<< keyframes.size() << std::endl;
  163. int num_processed = 0;
  164. for(int i = 0; i < std::min<int>(keyframe_queue.size(), max_keyframes_per_update); i++) {
  165. num_processed = i;
  166. const auto& keyframe = keyframe_queue[i];
  167. // new_keyframes will be tested later for loop closure
  168. new_keyframes.push_back(keyframe);
  169. // add pose node
  170. Eigen::Isometry3d odom = odom2map * keyframe->odom;
  171. keyframe->node = graph_slam->add_se3_node(odom);
  172. keyframe_hash[keyframe->stamp] = keyframe;
  173. // fix the first node
  174. if(keyframes.empty() && new_keyframes.size() == 1) {
  175. if(private_nh.param<bool>("fix_first_node", false)) {
  176. Eigen::MatrixXd inf = Eigen::MatrixXd::Identity(6, 6);
  177. std::stringstream sst(private_nh.param<std::string>("fix_first_node_stddev", "1 1 1 1 1 1"));
  178. for(int i = 0; i < 6; i++) {
  179. double stddev = 1.0;
  180. sst >> stddev;
  181. inf(i, i) = 1.0 / stddev;
  182. }
  183. anchor_node = graph_slam->add_se3_node(Eigen::Isometry3d::Identity());
  184. anchor_node->setFixed(true);
  185. anchor_edge = graph_slam->add_se3_edge(anchor_node, keyframe->node, Eigen::Isometry3d::Identity(), inf);
  186. }
  187. }
  188. if(i == 0 && keyframes.empty()) {
  189. continue;
  190. }
  191. // add edge between consecutive keyframes
  192. const auto& prev_keyframe = i == 0 ? keyframes.back() : keyframe_queue[i - 1];
  193. Eigen::Isometry3d relative_pose = keyframe->odom.inverse() * prev_keyframe->odom;
  194. Eigen::MatrixXd information = inf_calclator->calc_information_matrix(keyframe->cloud, prev_keyframe->cloud, relative_pose);
  195. auto edge = graph_slam->add_se3_edge(keyframe->node, prev_keyframe->node, relative_pose, information);
  196. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("odometry_edge_robust_kernel", "NONE"), private_nh.param<double>("odometry_edge_robust_kernel_size", 1.0));
  197. }
  198. std_msgs::Header read_until;
  199. read_until.stamp = keyframe_queue[num_processed]->stamp + ros::Duration(10, 0);
  200. read_until.frame_id = points_topic;
  201. read_until_pub.publish(read_until);
  202. read_until.frame_id = "/filtered_points";
  203. read_until_pub.publish(read_until);
  204. keyframe_queue.erase(keyframe_queue.begin(), keyframe_queue.begin() + num_processed + 1);
  205. return true;
  206. }
  207. void nmea_callback(const nmea_msgs::SentenceConstPtr& nmea_msg) {
  208. GPRMC grmc = nmea_parser->parse(nmea_msg->sentence);
  209. if(grmc.status != 'A') {
  210. return;
  211. }
  212. geographic_msgs::GeoPointStampedPtr gps_msg(new geographic_msgs::GeoPointStamped());
  213. gps_msg->header = nmea_msg->header;
  214. gps_msg->position.latitude = grmc.latitude;
  215. gps_msg->position.longitude = grmc.longitude;
  216. gps_msg->position.altitude = NAN;
  217. gps_callback(gps_msg);
  218. }
  219. void navsat_callback(const sensor_msgs::NavSatFixConstPtr& navsat_msg) {
  220. geographic_msgs::GeoPointStampedPtr gps_msg(new geographic_msgs::GeoPointStamped());
  221. gps_msg->header = navsat_msg->header;
  222. gps_msg->position.latitude = navsat_msg->latitude;
  223. gps_msg->position.longitude = navsat_msg->longitude;
  224. gps_msg->position.altitude = navsat_msg->altitude;
  225. gps_callback(gps_msg);
  226. }
  227. /**
  228. * @brief received gps data is added to #gps_queue
  229. * @param gps_msg
  230. */
  231. void gps_callback(const geographic_msgs::GeoPointStampedPtr& gps_msg) {
  232. std::lock_guard<std::mutex> lock(gps_queue_mutex);
  233. gps_msg->header.stamp += ros::Duration(gps_time_offset);
  234. gps_queue.push_back(gps_msg);
  235. }
  236. /**
  237. * @brief
  238. * @return
  239. */
  240. bool flush_gps_queue() {
  241. std::lock_guard<std::mutex> lock(gps_queue_mutex);
  242. if(keyframes.empty() || gps_queue.empty()) {
  243. return false;
  244. }
  245. bool updated = false;
  246. auto gps_cursor = gps_queue.begin();
  247. for(auto& keyframe : keyframes) {
  248. if(keyframe->stamp > gps_queue.back()->header.stamp) {
  249. break;
  250. }
  251. if(keyframe->stamp < (*gps_cursor)->header.stamp || keyframe->utm_coord) {
  252. continue;
  253. }
  254. // find the gps data which is closest to the keyframe
  255. auto closest_gps = gps_cursor;
  256. for(auto gps = gps_cursor; gps != gps_queue.end(); gps++) {
  257. auto dt = ((*closest_gps)->header.stamp - keyframe->stamp).toSec();
  258. auto dt2 = ((*gps)->header.stamp - keyframe->stamp).toSec();
  259. if(std::abs(dt) < std::abs(dt2)) {
  260. break;
  261. }
  262. closest_gps = gps;
  263. }
  264. // if the time residual between the gps and keyframe is too large, skip it
  265. gps_cursor = closest_gps;
  266. if(0.2 < std::abs(((*closest_gps)->header.stamp - keyframe->stamp).toSec())) {
  267. continue;
  268. }
  269. // convert (latitude, longitude, altitude) -> (easting, northing, altitude) in UTM coordinate
  270. geodesy::UTMPoint utm;
  271. geodesy::fromMsg((*closest_gps)->position, utm);
  272. Eigen::Vector3d xyz(utm.easting, utm.northing, utm.altitude);
  273. // the first gps data position will be the origin of the map
  274. if(!zero_utm) {
  275. zero_utm = xyz;
  276. }
  277. xyz -= (*zero_utm);
  278. keyframe->utm_coord = xyz;
  279. g2o::OptimizableGraph::Edge* edge;
  280. if(std::isnan(xyz.z())) {
  281. Eigen::Matrix2d information_matrix = Eigen::Matrix2d::Identity() / gps_edge_stddev_xy;
  282. edge = graph_slam->add_se3_prior_xy_edge(keyframe->node, xyz.head<2>(), information_matrix);
  283. } else {
  284. Eigen::Matrix3d information_matrix = Eigen::Matrix3d::Identity();
  285. information_matrix.block<2, 2>(0, 0) /= gps_edge_stddev_xy;
  286. information_matrix(2, 2) /= gps_edge_stddev_z;
  287. edge = graph_slam->add_se3_prior_xyz_edge(keyframe->node, xyz, information_matrix);
  288. }
  289. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("gps_edge_robust_kernel", "NONE"), private_nh.param<double>("gps_edge_robust_kernel_size", 1.0));
  290. updated = true;
  291. }
  292. auto remove_loc = std::upper_bound(gps_queue.begin(), gps_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const geographic_msgs::GeoPointStampedConstPtr& geopoint) { return stamp < geopoint->header.stamp; });
  293. gps_queue.erase(gps_queue.begin(), remove_loc);
  294. return updated;
  295. }
  296. void imu_callback(const sensor_msgs::ImuPtr& imu_msg) {
  297. if(!enable_imu_orientation && !enable_imu_acceleration) {
  298. return;
  299. }
  300. std::lock_guard<std::mutex> lock(imu_queue_mutex);
  301. imu_msg->header.stamp += ros::Duration(imu_time_offset);
  302. imu_queue.push_back(imu_msg);
  303. }
  304. bool flush_imu_queue() {
  305. std::lock_guard<std::mutex> lock(imu_queue_mutex);
  306. if(keyframes.empty() || imu_queue.empty() || base_frame_id.empty()) {
  307. return false;
  308. }
  309. bool updated = false;
  310. auto imu_cursor = imu_queue.begin();
  311. for(auto& keyframe : keyframes) {
  312. if(keyframe->stamp > imu_queue.back()->header.stamp) {
  313. break;
  314. }
  315. if(keyframe->stamp < (*imu_cursor)->header.stamp || keyframe->acceleration) {
  316. continue;
  317. }
  318. // find imu data which is closest to the keyframe
  319. auto closest_imu = imu_cursor;
  320. for(auto imu = imu_cursor; imu != imu_queue.end(); imu++) {
  321. auto dt = ((*closest_imu)->header.stamp - keyframe->stamp).toSec();
  322. auto dt2 = ((*imu)->header.stamp - keyframe->stamp).toSec();
  323. if(std::abs(dt) < std::abs(dt2)) {
  324. break;
  325. }
  326. closest_imu = imu;
  327. }
  328. imu_cursor = closest_imu;
  329. if(0.2 < std::abs(((*closest_imu)->header.stamp - keyframe->stamp).toSec())) {
  330. continue;
  331. }
  332. const auto& imu_ori = (*closest_imu)->orientation;
  333. const auto& imu_acc = (*closest_imu)->linear_acceleration;
  334. geometry_msgs::Vector3Stamped acc_imu;
  335. geometry_msgs::Vector3Stamped acc_base;
  336. geometry_msgs::QuaternionStamped quat_imu;
  337. geometry_msgs::QuaternionStamped quat_base;
  338. quat_imu.header.frame_id = acc_imu.header.frame_id = (*closest_imu)->header.frame_id;
  339. quat_imu.header.stamp = acc_imu.header.stamp = ros::Time(0);
  340. acc_imu.vector = (*closest_imu)->linear_acceleration;
  341. quat_imu.quaternion = (*closest_imu)->orientation;
  342. try {
  343. tf_listener.transformVector(base_frame_id, acc_imu, acc_base);
  344. tf_listener.transformQuaternion(base_frame_id, quat_imu, quat_base);
  345. } catch(std::exception& e) {
  346. std::cerr << "failed to find transform!!" << std::endl;
  347. return false;
  348. }
  349. keyframe->acceleration = Eigen::Vector3d(acc_base.vector.x, acc_base.vector.y, acc_base.vector.z);
  350. keyframe->orientation = Eigen::Quaterniond(quat_base.quaternion.w, quat_base.quaternion.x, quat_base.quaternion.y, quat_base.quaternion.z);
  351. keyframe->orientation = keyframe->orientation;
  352. if(keyframe->orientation->w() < 0.0) {
  353. keyframe->orientation->coeffs() = -keyframe->orientation->coeffs();
  354. }
  355. if(enable_imu_orientation) {
  356. Eigen::MatrixXd info = Eigen::MatrixXd::Identity(3, 3) / imu_orientation_edge_stddev;
  357. auto edge = graph_slam->add_se3_prior_quat_edge(keyframe->node, *keyframe->orientation, info);
  358. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("imu_orientation_edge_robust_kernel", "NONE"), private_nh.param<double>("imu_orientation_edge_robust_kernel_size", 1.0));
  359. }
  360. if(enable_imu_acceleration) {
  361. Eigen::MatrixXd info = Eigen::MatrixXd::Identity(3, 3) / imu_acceleration_edge_stddev;
  362. g2o::OptimizableGraph::Edge* edge = graph_slam->add_se3_prior_vec_edge(keyframe->node, -Eigen::Vector3d::UnitZ(), *keyframe->acceleration, info);
  363. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("imu_acceleration_edge_robust_kernel", "NONE"), private_nh.param<double>("imu_acceleration_edge_robust_kernel_size", 1.0));
  364. }
  365. updated = true;
  366. }
  367. auto remove_loc = std::upper_bound(imu_queue.begin(), imu_queue.end(), keyframes.back()->stamp, [=](const ros::Time& stamp, const sensor_msgs::ImuConstPtr& imu) { return stamp < imu->header.stamp; });
  368. imu_queue.erase(imu_queue.begin(), remove_loc);
  369. return updated;
  370. }
  371. /**
  372. * @brief received floor coefficients are added to #floor_coeffs_queue
  373. * @param floor_coeffs_msg
  374. */
  375. void floor_coeffs_callback(const hdl_graph_slam::FloorCoeffsConstPtr& floor_coeffs_msg) {
  376. if(floor_coeffs_msg->coeffs.empty()) {
  377. return;
  378. }
  379. std::lock_guard<std::mutex> lock(floor_coeffs_queue_mutex);
  380. floor_coeffs_queue.push_back(floor_coeffs_msg);
  381. }
  382. /**
  383. * @brief this methods associates floor coefficients messages with registered keyframes, and then adds the associated coeffs to the pose graph
  384. * @return if true, at least one floor plane edge is added to the pose graph
  385. */
  386. bool flush_floor_queue() {
  387. std::lock_guard<std::mutex> lock(floor_coeffs_queue_mutex);
  388. if(keyframes.empty()) {
  389. return false;
  390. }
  391. const auto& latest_keyframe_stamp = keyframes.back()->stamp;
  392. bool updated = false;
  393. for(const auto& floor_coeffs : floor_coeffs_queue) {
  394. if(floor_coeffs->header.stamp > latest_keyframe_stamp) {
  395. break;
  396. }
  397. auto found = keyframe_hash.find(floor_coeffs->header.stamp);
  398. if(found == keyframe_hash.end()) {
  399. continue;
  400. }
  401. if(!floor_plane_node) {
  402. floor_plane_node = graph_slam->add_plane_node(Eigen::Vector4d(0.0, 0.0, 1.0, 0.0));
  403. floor_plane_node->setFixed(true);
  404. }
  405. const auto& keyframe = found->second;
  406. Eigen::Vector4d coeffs(floor_coeffs->coeffs[0], floor_coeffs->coeffs[1], floor_coeffs->coeffs[2], floor_coeffs->coeffs[3]);
  407. Eigen::Matrix3d information = Eigen::Matrix3d::Identity() * (1.0 / floor_edge_stddev);
  408. auto edge = graph_slam->add_se3_plane_edge(keyframe->node, floor_plane_node, coeffs, information);
  409. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("floor_edge_robust_kernel", "NONE"), private_nh.param<double>("floor_edge_robust_kernel_size", 1.0));
  410. keyframe->floor_coeffs = coeffs;
  411. updated = true;
  412. }
  413. auto remove_loc = std::upper_bound(floor_coeffs_queue.begin(), floor_coeffs_queue.end(), latest_keyframe_stamp, [=](const ros::Time& stamp, const hdl_graph_slam::FloorCoeffsConstPtr& coeffs) { return stamp < coeffs->header.stamp; });
  414. floor_coeffs_queue.erase(floor_coeffs_queue.begin(), remove_loc);
  415. return updated;
  416. }
  417. /**
  418. * @brief generate map point cloud and publish it
  419. * @param event
  420. */
  421. void map_points_publish_timer_callback(const ros::WallTimerEvent& event) {
  422. if(!map_points_pub.getNumSubscribers() || !graph_updated) {
  423. return;
  424. }
  425. std::vector<KeyFrameSnapshot::Ptr> snapshot;
  426. keyframes_snapshot_mutex.lock();
  427. snapshot = keyframes_snapshot;
  428. keyframes_snapshot_mutex.unlock();
  429. auto cloud = map_cloud_generator->generate(snapshot, map_cloud_resolution);
  430. if(!cloud) {
  431. return;
  432. }
  433. cloud->header.frame_id = map_frame_id;
  434. cloud->header.stamp = snapshot.back()->cloud->header.stamp;
  435. sensor_msgs::PointCloud2Ptr cloud_msg(new sensor_msgs::PointCloud2());
  436. pcl::toROSMsg(*cloud, *cloud_msg);
  437. map_points_pub.publish(cloud_msg);
  438. }
  439. /**
  440. * @brief this methods adds all the data in the queues to the pose graph, and then optimizes the pose graph
  441. * @param event
  442. */
  443. void optimization_timer_callback(const ros::WallTimerEvent& event) {
  444. std::lock_guard<std::mutex> lock(main_thread_mutex);
  445. // add keyframes and floor coeffs in the queues to the pose graph
  446. bool keyframe_updated = flush_keyframe_queue();
  447. if(!keyframe_updated) {
  448. std_msgs::Header read_until;
  449. read_until.stamp = ros::Time::now() + ros::Duration(30, 0);
  450. read_until.frame_id = points_topic;
  451. read_until_pub.publish(read_until);
  452. read_until.frame_id = "/filtered_points";
  453. read_until_pub.publish(read_until);
  454. }
  455. if(!keyframe_updated & !flush_floor_queue() & !flush_gps_queue() & !flush_imu_queue()) {
  456. return;
  457. }
  458. // loop detection
  459. std::vector<Loop::Ptr> loops = loop_detector->detect(keyframes, new_keyframes, *graph_slam);
  460. for(const auto& loop : loops) {
  461. Eigen::Isometry3d relpose(loop->relative_pose.cast<double>());
  462. Eigen::MatrixXd information_matrix = inf_calclator->calc_information_matrix(loop->key1->cloud, loop->key2->cloud, relpose);
  463. auto edge = graph_slam->add_se3_edge(loop->key1->node, loop->key2->node, relpose, information_matrix);
  464. graph_slam->add_robust_kernel(edge, private_nh.param<std::string>("loop_closure_edge_robust_kernel", "NONE"), private_nh.param<double>("loop_closure_edge_robust_kernel_size", 1.0));
  465. }
  466. std::copy(new_keyframes.begin(), new_keyframes.end(), std::back_inserter(keyframes));
  467. new_keyframes.clear();
  468. // move the first node anchor position to the current estimate of the first node pose
  469. // so the first node moves freely while trying to stay around the origin
  470. if(anchor_node && private_nh.param<bool>("fix_first_node_adaptive", true)) {
  471. Eigen::Isometry3d anchor_target = static_cast<g2o::VertexSE3*>(anchor_edge->vertices()[1])->estimate();
  472. anchor_node->setEstimate(anchor_target);
  473. }
  474. // optimize the pose graph
  475. int num_iterations = private_nh.param<int>("g2o_solver_num_iterations", 1024);
  476. graph_slam->optimize(num_iterations);
  477. // publish tf
  478. const auto& keyframe = keyframes.back();
  479. Eigen::Isometry3d trans = keyframe->node->estimate() * keyframe->odom.inverse();
  480. trans_odom2map_mutex.lock();
  481. trans_odom2map = trans.matrix().cast<float>();
  482. trans_odom2map_mutex.unlock();
  483. std::vector<KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
  484. std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const KeyFrame::Ptr& k) { return std::make_shared<KeyFrameSnapshot>(k); });
  485. keyframes_snapshot_mutex.lock();
  486. keyframes_snapshot.swap(snapshot);
  487. keyframes_snapshot_mutex.unlock();
  488. graph_updated = true;
  489. if(odom2map_pub.getNumSubscribers()) {
  490. geometry_msgs::TransformStamped ts = matrix2transform(keyframe->stamp, trans.matrix().cast<float>(), map_frame_id, odom_frame_id);
  491. odom2map_pub.publish(ts);
  492. }
  493. if(markers_pub.getNumSubscribers()) {
  494. auto markers = create_marker_array(ros::Time::now());
  495. markers_pub.publish(markers);
  496. }
  497. }
  498. /**
  499. * @brief create visualization marker
  500. * @param stamp
  501. * @return
  502. */
  503. visualization_msgs::MarkerArray create_marker_array(const ros::Time& stamp) const {
  504. visualization_msgs::MarkerArray markers;
  505. markers.markers.resize(4);
  506. // node markers
  507. visualization_msgs::Marker& traj_marker = markers.markers[0];
  508. traj_marker.header.frame_id = "map";
  509. traj_marker.header.stamp = stamp;
  510. traj_marker.ns = "nodes";
  511. traj_marker.id = 0;
  512. traj_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  513. traj_marker.pose.orientation.w = 1.0;
  514. traj_marker.scale.x = traj_marker.scale.y = traj_marker.scale.z = 0.5;
  515. visualization_msgs::Marker& imu_marker = markers.markers[1];
  516. imu_marker.header = traj_marker.header;
  517. imu_marker.ns = "imu";
  518. imu_marker.id = 1;
  519. imu_marker.type = visualization_msgs::Marker::SPHERE_LIST;
  520. imu_marker.pose.orientation.w = 1.0;
  521. imu_marker.scale.x = imu_marker.scale.y = imu_marker.scale.z = 0.75;
  522. traj_marker.points.resize(keyframes.size());
  523. traj_marker.colors.resize(keyframes.size());
  524. for(int i = 0; i < keyframes.size(); i++) {
  525. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  526. traj_marker.points[i].x = pos.x();
  527. traj_marker.points[i].y = pos.y();
  528. traj_marker.points[i].z = pos.z();
  529. double p = static_cast<double>(i) / keyframes.size();
  530. traj_marker.colors[i].r = 1.0 - p;
  531. traj_marker.colors[i].g = p;
  532. traj_marker.colors[i].b = 0.0;
  533. traj_marker.colors[i].a = 1.0;
  534. if(keyframes[i]->acceleration) {
  535. Eigen::Vector3d pos = keyframes[i]->node->estimate().translation();
  536. geometry_msgs::Point point;
  537. point.x = pos.x();
  538. point.y = pos.y();
  539. point.z = pos.z();
  540. std_msgs::ColorRGBA color;
  541. color.r = 0.0;
  542. color.g = 0.0;
  543. color.b = 1.0;
  544. color.a = 0.1;
  545. imu_marker.points.push_back(point);
  546. imu_marker.colors.push_back(color);
  547. }
  548. }
  549. // edge markers
  550. visualization_msgs::Marker& edge_marker = markers.markers[2];
  551. edge_marker.header.frame_id = "map";
  552. edge_marker.header.stamp = stamp;
  553. edge_marker.ns = "edges";
  554. edge_marker.id = 2;
  555. edge_marker.type = visualization_msgs::Marker::LINE_LIST;
  556. edge_marker.pose.orientation.w = 1.0;
  557. edge_marker.scale.x = 0.05;
  558. edge_marker.points.resize(graph_slam->graph->edges().size() * 2);
  559. edge_marker.colors.resize(graph_slam->graph->edges().size() * 2);
  560. auto edge_itr = graph_slam->graph->edges().begin();
  561. for(int i = 0; edge_itr != graph_slam->graph->edges().end(); edge_itr++, i++) {
  562. g2o::HyperGraph::Edge* edge = *edge_itr;
  563. g2o::EdgeSE3* edge_se3 = dynamic_cast<g2o::EdgeSE3*>(edge);
  564. if(edge_se3) {
  565. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[0]);
  566. g2o::VertexSE3* v2 = dynamic_cast<g2o::VertexSE3*>(edge_se3->vertices()[1]);
  567. Eigen::Vector3d pt1 = v1->estimate().translation();
  568. Eigen::Vector3d pt2 = v2->estimate().translation();
  569. edge_marker.points[i * 2].x = pt1.x();
  570. edge_marker.points[i * 2].y = pt1.y();
  571. edge_marker.points[i * 2].z = pt1.z();
  572. edge_marker.points[i * 2 + 1].x = pt2.x();
  573. edge_marker.points[i * 2 + 1].y = pt2.y();
  574. edge_marker.points[i * 2 + 1].z = pt2.z();
  575. double p1 = static_cast<double>(v1->id()) / graph_slam->graph->vertices().size();
  576. double p2 = static_cast<double>(v2->id()) / graph_slam->graph->vertices().size();
  577. edge_marker.colors[i * 2].r = 1.0 - p1;
  578. edge_marker.colors[i * 2].g = p1;
  579. edge_marker.colors[i * 2].a = 1.0;
  580. edge_marker.colors[i * 2 + 1].r = 1.0 - p2;
  581. edge_marker.colors[i * 2 + 1].g = p2;
  582. edge_marker.colors[i * 2 + 1].a = 1.0;
  583. if(std::abs(v1->id() - v2->id()) > 2) {
  584. edge_marker.points[i * 2].z += 0.5;
  585. edge_marker.points[i * 2 + 1].z += 0.5;
  586. }
  587. continue;
  588. }
  589. g2o::EdgeSE3Plane* edge_plane = dynamic_cast<g2o::EdgeSE3Plane*>(edge);
  590. if(edge_plane) {
  591. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_plane->vertices()[0]);
  592. Eigen::Vector3d pt1 = v1->estimate().translation();
  593. Eigen::Vector3d pt2(pt1.x(), pt1.y(), 0.0);
  594. edge_marker.points[i * 2].x = pt1.x();
  595. edge_marker.points[i * 2].y = pt1.y();
  596. edge_marker.points[i * 2].z = pt1.z();
  597. edge_marker.points[i * 2 + 1].x = pt2.x();
  598. edge_marker.points[i * 2 + 1].y = pt2.y();
  599. edge_marker.points[i * 2 + 1].z = pt2.z();
  600. edge_marker.colors[i * 2].b = 1.0;
  601. edge_marker.colors[i * 2].a = 1.0;
  602. edge_marker.colors[i * 2 + 1].b = 1.0;
  603. edge_marker.colors[i * 2 + 1].a = 1.0;
  604. continue;
  605. }
  606. g2o::EdgeSE3PriorXY* edge_priori_xy = dynamic_cast<g2o::EdgeSE3PriorXY*>(edge);
  607. if(edge_priori_xy) {
  608. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xy->vertices()[0]);
  609. Eigen::Vector3d pt1 = v1->estimate().translation();
  610. Eigen::Vector3d pt2 = Eigen::Vector3d::Zero();
  611. pt2.head<2>() = edge_priori_xy->measurement();
  612. edge_marker.points[i * 2].x = pt1.x();
  613. edge_marker.points[i * 2].y = pt1.y();
  614. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  615. edge_marker.points[i * 2 + 1].x = pt2.x();
  616. edge_marker.points[i * 2 + 1].y = pt2.y();
  617. edge_marker.points[i * 2 + 1].z = pt2.z() + 0.5;
  618. edge_marker.colors[i * 2].r = 1.0;
  619. edge_marker.colors[i * 2].a = 1.0;
  620. edge_marker.colors[i * 2 + 1].r = 1.0;
  621. edge_marker.colors[i * 2 + 1].a = 1.0;
  622. continue;
  623. }
  624. g2o::EdgeSE3PriorXYZ* edge_priori_xyz = dynamic_cast<g2o::EdgeSE3PriorXYZ*>(edge);
  625. if(edge_priori_xyz) {
  626. g2o::VertexSE3* v1 = dynamic_cast<g2o::VertexSE3*>(edge_priori_xyz->vertices()[0]);
  627. Eigen::Vector3d pt1 = v1->estimate().translation();
  628. Eigen::Vector3d pt2 = edge_priori_xyz->measurement();
  629. edge_marker.points[i * 2].x = pt1.x();
  630. edge_marker.points[i * 2].y = pt1.y();
  631. edge_marker.points[i * 2].z = pt1.z() + 0.5;
  632. edge_marker.points[i * 2 + 1].x = pt2.x();
  633. edge_marker.points[i * 2 + 1].y = pt2.y();
  634. edge_marker.points[i * 2 + 1].z = pt2.z();
  635. edge_marker.colors[i * 2].r = 1.0;
  636. edge_marker.colors[i * 2].a = 1.0;
  637. edge_marker.colors[i * 2 + 1].r = 1.0;
  638. edge_marker.colors[i * 2 + 1].a = 1.0;
  639. continue;
  640. }
  641. }
  642. // sphere
  643. visualization_msgs::Marker& sphere_marker = markers.markers[3];
  644. sphere_marker.header.frame_id = "map";
  645. sphere_marker.header.stamp = stamp;
  646. sphere_marker.ns = "loop_close_radius";
  647. sphere_marker.id = 3;
  648. sphere_marker.type = visualization_msgs::Marker::SPHERE;
  649. if(!keyframes.empty()) {
  650. Eigen::Vector3d pos = keyframes.back()->node->estimate().translation();
  651. sphere_marker.pose.position.x = pos.x();
  652. sphere_marker.pose.position.y = pos.y();
  653. sphere_marker.pose.position.z = pos.z();
  654. }
  655. sphere_marker.pose.orientation.w = 1.0;
  656. sphere_marker.scale.x = sphere_marker.scale.y = sphere_marker.scale.z = loop_detector->get_distance_thresh() * 2.0;
  657. sphere_marker.color.r = 1.0;
  658. sphere_marker.color.a = 0.3;
  659. return markers;
  660. }
  661. /**
  662. * @brief load all data from a directory
  663. * @param req
  664. * @param res
  665. * @return
  666. */
  667. bool load_service(hdl_graph_slam::LoadGraphRequest& req, hdl_graph_slam::LoadGraphResponse& res) {
  668. std::lock_guard<std::mutex> lock(main_thread_mutex);
  669. std::string directory = req.path;
  670. std::cout << "loading data from:" << directory << std::endl;
  671. // Load graph.
  672. graph_slam->load(directory + "/graph.g2o");
  673. // Iterate over the items in this directory and count how many sub directories there are.
  674. // This will give an upper limit on how many keyframe indexes we can expect to find.
  675. boost::filesystem::directory_iterator begin(directory), end;
  676. int max_directory_count = std::count_if(begin, end,
  677. [](const boost::filesystem::directory_entry & d) {
  678. return boost::filesystem::is_directory(d.path()); // only return true if a direcotry
  679. });
  680. // Load keyframes by looping through key frame indexes that we expect to see.
  681. for(int i = 0; i < max_directory_count; i++) {
  682. std::stringstream sst;
  683. sst << boost::format("%s/%06d") % directory % i;
  684. std::string key_frame_directory = sst.str();
  685. // If key_frame_directory doesnt exist, then we have run out so lets stop looking.
  686. if(!boost::filesystem::is_directory(key_frame_directory)) {
  687. break;
  688. }
  689. KeyFrame::Ptr keyframe(new KeyFrame(key_frame_directory, graph_slam->graph.get()));
  690. keyframes.push_back(keyframe);
  691. }
  692. std::cout << "loaded " << keyframes.size() << " keyframes" <<std::endl;
  693. // Load special nodes.
  694. std::ifstream ifs(directory + "/special_nodes.csv");
  695. if(!ifs) {
  696. return false;
  697. }
  698. while(!ifs.eof()) {
  699. std::string token;
  700. ifs >> token;
  701. if(token == "anchor_node") {
  702. int id = 0;
  703. ifs >> id;
  704. anchor_node = static_cast<g2o::VertexSE3*>(graph_slam->graph->vertex(id));
  705. } else if(token == "anchor_edge") {
  706. int id = 0;
  707. ifs >> id;
  708. // We have no way of directly pulling the edge based on the edge ID that we have just read in.
  709. // Fortunatly anchor edges are always attached to the anchor node so we can iterate over
  710. // the edges that listed against the node untill we find the one that matches our ID.
  711. if(anchor_node){
  712. auto edges = anchor_node->edges();
  713. for(auto e : edges) {
  714. int edgeID = e->id();
  715. if (edgeID == id){
  716. anchor_edge = static_cast<g2o::EdgeSE3*>(e);
  717. break;
  718. }
  719. }
  720. }
  721. } else if(token == "floor_node") {
  722. int id = 0;
  723. ifs >> id;
  724. floor_plane_node = static_cast<g2o::VertexPlane*>(graph_slam->graph->vertex(id));
  725. }
  726. }
  727. // check if we have any non null special nodes, if all are null then lets not bother.
  728. if(anchor_node->id() || anchor_edge->id() || floor_plane_node->id()) {
  729. std::cout << "loaded special nodes - ";
  730. // check exists before printing information about each special node
  731. if(anchor_node->id()) {
  732. std::cout << " anchor_node: " << anchor_node->id();
  733. }
  734. if(anchor_edge->id()) {
  735. std::cout << " anchor_edge: " << anchor_edge->id();
  736. }
  737. if(floor_plane_node->id()) {
  738. std::cout << " floor_node: " << floor_plane_node->id();
  739. }
  740. // finish with a new line
  741. std::cout << std::endl;
  742. }
  743. // Update our keyframe snapshot so we can publish a map update, trigger update with graph_updated = true.
  744. std::vector<KeyFrameSnapshot::Ptr> snapshot(keyframes.size());
  745. std::transform(keyframes.begin(), keyframes.end(), snapshot.begin(), [=](const KeyFrame::Ptr& k) { return std::make_shared<KeyFrameSnapshot>(k); });
  746. keyframes_snapshot_mutex.lock();
  747. keyframes_snapshot.swap(snapshot);
  748. keyframes_snapshot_mutex.unlock();
  749. graph_updated = true;
  750. res.success = true;
  751. std::cout << "snapshot updated" << std::endl << "loading successful" <<std::endl;
  752. return true;
  753. }
  754. /**
  755. * @brief dump all data to the current directory
  756. * @param req
  757. * @param res
  758. * @return
  759. */
  760. bool dump_service(hdl_graph_slam::DumpGraphRequest& req, hdl_graph_slam::DumpGraphResponse& res) {
  761. std::lock_guard<std::mutex> lock(main_thread_mutex);
  762. std::string directory = req.destination;
  763. if(directory.empty()) {
  764. std::array<char, 64> buffer;
  765. buffer.fill(0);
  766. time_t rawtime;
  767. time(&rawtime);
  768. const auto timeinfo = localtime(&rawtime);
  769. strftime(buffer.data(), sizeof(buffer), "%d-%m-%Y %H:%M:%S", timeinfo);
  770. }
  771. if(!boost::filesystem::is_directory(directory)) {
  772. boost::filesystem::create_directory(directory);
  773. }
  774. std::cout << "dumping data to:" << directory << std::endl;
  775. // save graph
  776. graph_slam->save(directory + "/graph.g2o");
  777. // save keyframes
  778. for(int i = 0; i < keyframes.size(); i++) {
  779. std::stringstream sst;
  780. sst << boost::format("%s/%06d") % directory % i;
  781. keyframes[i]->save(sst.str());
  782. }
  783. if(zero_utm) {
  784. std::ofstream zero_utm_ofs(directory + "/zero_utm");
  785. zero_utm_ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
  786. }
  787. std::ofstream ofs(directory + "/special_nodes.csv");
  788. ofs << "anchor_node " << (anchor_node == nullptr ? -1 : anchor_node->id()) << std::endl;
  789. ofs << "anchor_edge " << (anchor_edge == nullptr ? -1 : anchor_edge->id()) << std::endl;
  790. ofs << "floor_node " << (floor_plane_node == nullptr ? -1 : floor_plane_node->id()) << std::endl;
  791. res.success = true;
  792. return true;
  793. }
  794. /**
  795. * @brief save map data as pcd
  796. * @param req
  797. * @param res
  798. * @return
  799. */
  800. bool save_map_service(hdl_graph_slam::SaveMapRequest& req, hdl_graph_slam::SaveMapResponse& res) {
  801. std::vector<KeyFrameSnapshot::Ptr> snapshot;
  802. keyframes_snapshot_mutex.lock();
  803. snapshot = keyframes_snapshot;
  804. keyframes_snapshot_mutex.unlock();
  805. auto cloud = map_cloud_generator->generate(snapshot, req.resolution);
  806. if(!cloud) {
  807. res.success = false;
  808. return true;
  809. }
  810. if(zero_utm && req.utm) {
  811. for(auto& pt : cloud->points) {
  812. pt.getVector3fMap() += (*zero_utm).cast<float>();
  813. }
  814. }
  815. cloud->header.frame_id = map_frame_id;
  816. cloud->header.stamp = snapshot.back()->cloud->header.stamp;
  817. if(zero_utm) {
  818. std::ofstream ofs(req.destination + ".utm");
  819. ofs << boost::format("%.6f %.6f %.6f") % zero_utm->x() % zero_utm->y() % zero_utm->z() << std::endl;
  820. }
  821. int ret = pcl::io::savePCDFileBinary(req.destination, *cloud);
  822. res.success = ret == 0;
  823. return true;
  824. }
  825. private:
  826. // ROS
  827. ros::NodeHandle nh;
  828. ros::NodeHandle mt_nh;
  829. ros::NodeHandle private_nh;
  830. ros::WallTimer optimization_timer;
  831. ros::WallTimer map_publish_timer;
  832. std::unique_ptr<message_filters::Subscriber<nav_msgs::Odometry>> odom_sub;
  833. std::unique_ptr<message_filters::Subscriber<sensor_msgs::PointCloud2>> cloud_sub;
  834. std::unique_ptr<message_filters::Synchronizer<ApproxSyncPolicy>> sync;
  835. ros::Subscriber gps_sub;
  836. ros::Subscriber nmea_sub;
  837. ros::Subscriber navsat_sub;
  838. ros::Subscriber imu_sub;
  839. ros::Subscriber floor_sub;
  840. ros::Publisher markers_pub;
  841. std::string published_odom_topic;
  842. std::string map_frame_id;
  843. std::string odom_frame_id;
  844. std::mutex trans_odom2map_mutex;
  845. Eigen::Matrix4f trans_odom2map;
  846. ros::Publisher odom2map_pub;
  847. std::string points_topic;
  848. ros::Publisher read_until_pub;
  849. ros::Publisher map_points_pub;
  850. tf::TransformListener tf_listener;
  851. ros::ServiceServer load_service_server;
  852. ros::ServiceServer dump_service_server;
  853. ros::ServiceServer save_map_service_server;
  854. // keyframe queue
  855. std::string base_frame_id;
  856. std::mutex keyframe_queue_mutex;
  857. std::deque<KeyFrame::Ptr> keyframe_queue;
  858. // gps queue
  859. double gps_time_offset;
  860. double gps_edge_stddev_xy;
  861. double gps_edge_stddev_z;
  862. boost::optional<Eigen::Vector3d> zero_utm;
  863. std::mutex gps_queue_mutex;
  864. std::deque<geographic_msgs::GeoPointStampedConstPtr> gps_queue;
  865. // imu queue
  866. double imu_time_offset;
  867. bool enable_imu_orientation;
  868. double imu_orientation_edge_stddev;
  869. bool enable_imu_acceleration;
  870. double imu_acceleration_edge_stddev;
  871. std::mutex imu_queue_mutex;
  872. std::deque<sensor_msgs::ImuConstPtr> imu_queue;
  873. // floor_coeffs queue
  874. double floor_edge_stddev;
  875. std::mutex floor_coeffs_queue_mutex;
  876. std::deque<hdl_graph_slam::FloorCoeffsConstPtr> floor_coeffs_queue;
  877. // for map cloud generation
  878. std::atomic_bool graph_updated;
  879. double map_cloud_resolution;
  880. std::mutex keyframes_snapshot_mutex;
  881. std::vector<KeyFrameSnapshot::Ptr> keyframes_snapshot;
  882. std::unique_ptr<MapCloudGenerator> map_cloud_generator;
  883. // graph slam
  884. // all the below members must be accessed after locking main_thread_mutex
  885. std::mutex main_thread_mutex;
  886. int max_keyframes_per_update;
  887. std::deque<KeyFrame::Ptr> new_keyframes;
  888. g2o::VertexSE3* anchor_node;
  889. g2o::EdgeSE3* anchor_edge;
  890. g2o::VertexPlane* floor_plane_node;
  891. std::vector<KeyFrame::Ptr> keyframes;
  892. std::unordered_map<ros::Time, KeyFrame::Ptr, RosTimeHash> keyframe_hash;
  893. std::unique_ptr<GraphSLAM> graph_slam;
  894. std::unique_ptr<LoopDetector> loop_detector;
  895. std::unique_ptr<KeyframeUpdater> keyframe_updater;
  896. std::unique_ptr<NmeaSentenceParser> nmea_parser;
  897. std::unique_ptr<InformationMatrixCalculator> inf_calclator;
  898. };
  899. } // namespace hdl_graph_slam
  900. PLUGINLIB_EXPORT_CLASS(hdl_graph_slam::HdlGraphSlamNodelet, nodelet::Nodelet)