slam.cpp 40 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950
  1. #include "pose_graph/pose_cost_function.h"
  2. #include "slam/slam.h"
  3. #include "filter/filter.h"
  4. #include "pose_graph/occupied_space_cost_function.h"
  5. #include "pose_graph/rotation_delta_cost_functor.h"
  6. #include "pose_graph/translation_delta_cost_functor.h"
  7. #include "pose_graph/pose_graph.h"
  8. namespace hlzn_slam {
  9. namespace slam {
  10. Slam::Slam(std::unique_ptr<Map> global_map) :
  11. is_initialize_(false),
  12. global_map_(std::move(global_map)),
  13. use_towermatch_(true),
  14. probability_plus_(0.2),
  15. probability_up_(0.8),
  16. search_range_(0.3),
  17. search_angle_(0.1),
  18. window_size_(20),
  19. achieve_range_(0.5),
  20. achieve_angle_(0.4),
  21. first_search_range_(5.0),
  22. first_search_angle_(M_PI),
  23. v_(0.0),
  24. w_(0.0)
  25. {
  26. odom_ = std::unique_ptr<odom::odom>(new odom::odom());
  27. global_map_->useShadow(true);
  28. }
  29. Slam::~Slam()
  30. {
  31. while (matchThread_.joinable()) {
  32. usleep(1000 * 10);
  33. }
  34. }
  35. bool Slam::isInitialize()
  36. {
  37. return is_initialize_;
  38. }
  39. void Slam::init(const common::Rigid2f& init, bool is_fast, float first_search_range, float first_search_angle)
  40. {
  41. TIME_POSE_LOCK()
  42. if (!is_fast) {
  43. time_pose_.pose = init;
  44. is_initialize_ = false;
  45. }
  46. else {
  47. time_pose_.pose = init;
  48. time_pose_.stamp = std::chrono::system_clock::now();
  49. is_initialize_ = true;
  50. odom_pose_ = time_pose_;
  51. }
  52. first_search_range_ = first_search_range;
  53. first_search_angle_ = first_search_angle;
  54. }
  55. void Slam::setParam(float search_range, float search_angle, bool use_towermatch, float probability_plus, float probability_up,
  56. int window_size, float achieve_range, float achieve_angle, float submap_size, float submap_resolution, bool use_odom)
  57. {
  58. probability_plus_ = probability_plus;
  59. use_towermatch_ = use_towermatch;
  60. use_odom_ = use_odom;
  61. probability_up_ = probability_up;
  62. search_range_ = search_range;
  63. search_angle_ = search_angle;
  64. window_size_ = window_size;
  65. achieve_range_ = achieve_range;
  66. achieve_angle_ = achieve_angle;
  67. submap_size_ = submap_size;
  68. submap_resolution_ = submap_resolution;
  69. }
  70. void Slam::addPointCloud(common::PointCloud point_cloud, common::laserScan scan, Eigen::Matrix<float, 4, 4> tf) // 唯一入口
  71. {
  72. if (!matchThread_.joinable()) {
  73. matchThread_ = std::thread([this, point_cloud, scan, tf] {
  74. scan_ = scan;
  75. laser_tf_ = tf;
  76. __slam(point_cloud);
  77. matchThread_.detach();
  78. });
  79. }
  80. }
  81. void Slam::addOriginScan(common::laserScan& scan, Eigen::Matrix<float, 4, 4>& tf)
  82. {
  83. common::PointCloud point_cloud;
  84. float theta = scan.angle_max;
  85. float offset = scan.angle_max + scan.angle_min;
  86. for (const float& range : scan.ranges) {
  87. theta -= scan.angle_increment;
  88. if (range > scan.range_max) continue;
  89. if (range < scan.range_min) continue;
  90. if (theta < scan.angle_min) continue;
  91. if (theta > scan.angle_max) continue;
  92. if (std::isnan(range)) continue;
  93. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  94. -range * sin(theta - offset),
  95. 0.0,
  96. 1.0);
  97. //将基于传感器坐标系的数据转到基于base_link坐标系
  98. Eigen::Matrix<float, 4, 1> base = tf * point;
  99. point_cloud.data.push_back(
  100. Eigen::Vector3f(base(0), base(1), base(2))
  101. );
  102. }
  103. }
  104. void Slam::addOdom2DVelocity(float& v, float& w)
  105. {
  106. TIME_POSE_LOCK()
  107. v_ = v;
  108. w_ = w;
  109. }
  110. void Slam::addOdom2D(float& x, float& y, float& theta)
  111. {
  112. TIME_POSE_LOCK()
  113. odom_->addOdometry(x, y, theta);
  114. }
  115. common::TimeRigid2f Slam::getCurrentPose()
  116. {
  117. TIME_POSE_LOCK()
  118. return time_pose_;
  119. }
  120. void Slam::__slam(common::PointCloud point_cloud)
  121. {
  122. common::Rigid2f global_pose = getCurrentPose().pose;
  123. common::Rigid2f track_pose = common::Rigid2f({0.0, 0.0}, 0.0);
  124. if (!is_initialize_) {
  125. RealTimeMatch2D matcher;
  126. common::PointCloud filter = filter::VoxelInterpolationFilter(point_cloud, 0.5);// global_map_->getResolution() * 10.0);
  127. matcher.setSearchRange(first_search_range_, first_search_angle_, 0.1, 0.17);// global_map_->getResolution() * 2.0, 0.017 * 10.0);
  128. matcher.match(filter, getCurrentPose().pose, global_pose, *global_map_);
  129. is_initialize_ = true;
  130. }
  131. if (!submaps_.empty()) { // 局部地图匹配
  132. static common::Time clock = std::chrono::system_clock::now();
  133. std::chrono::duration<float> dur = std::chrono::system_clock::now() - clock;
  134. common::Rigid2f perticet;
  135. static common::Rigid2f odom({0, 0}, 0);
  136. float l = v_ * dur.count();
  137. float w = w_ * dur.count();
  138. perticet = common::Rigid2f({l * cos(w), l * sin(w)}, w);
  139. // odom_->extrapolaOdom(clock, std::chrono::system_clock::now(), perticet);
  140. odom_pose_.pose = odom_pose_.pose * perticet;
  141. clock = std::chrono::system_clock::now();
  142. float range = dur.count() * 3.0; // 3m/s的速度运行
  143. float rad = dur.count() * 1.0; // 3rad/s的速度旋转
  144. range = range > 0.3 ? 0.3 : range;
  145. rad = rad > 0.17 ? 0.17 : rad;
  146. #define POSEGRAPH2 0
  147. #if POSEGRAPH2
  148. for (std::shared_ptr<SubMap> submap : submaps_) {
  149. common::Rigid2f tmp = submap->track_pose * perticet;
  150. submap->track_pose = __Match(tmp, point_cloud, *submap->map, range, rad,
  151. 10.0, 2.0, 3.0, 1.0);
  152. LOG(INFO)<<""<<submap->track_pose.translation()(0);
  153. LOG(INFO)<<""<<submap->track_pose.translation()(1);
  154. LOG(INFO)<<""<<submap->track_pose.rotation().angle();
  155. LOG(INFO)<<"***********************";
  156. }
  157. LOG(INFO)<<"*************************************************";
  158. global_pose = submaps_.back()->global_pose * submaps_.back()->track_pose;
  159. #else
  160. common::Rigid2f track_pose_perticet = submaps_.back()->track_pose * perticet;
  161. track_pose = __Match(track_pose_perticet, point_cloud, *submaps_.back()->map, range, rad);
  162. global_pose = submaps_.back()->global_pose * track_pose;
  163. #endif
  164. }
  165. { // 全局地图匹配
  166. global_pose = __Match(global_pose, point_cloud, *global_map_, search_range_, search_angle_,
  167. 1.0, 2.0, 3.0, 1.0);
  168. }
  169. bool compir_success = false;
  170. if (!submaps_.empty()) {
  171. #if POSEGRAPH2
  172. __poseGraph2(global_pose);
  173. #else
  174. common::Rigid2f error = odom_pose_.pose.inverse() * global_pose;
  175. if ((error.translation().norm() > search_range_ || fabs(error.rotation().angle()) > search_angle_) && use_odom_) {
  176. float compir_cost1 = global_map_->getCost(__transformPointCloud(point_cloud, global_pose));
  177. common::Rigid2f maybe = __Match(odom_pose_.pose, point_cloud, *global_map_, search_range_, search_angle_);
  178. float compir_cost2 = global_map_->getCost(__transformPointCloud(point_cloud, maybe));
  179. if (compir_cost2 > compir_cost1 * 1.2) {
  180. global_pose = maybe;
  181. odom_pose_.pose = maybe;
  182. compir_success = true;
  183. }
  184. }
  185. // __poseGraph(global_pose, track_pose);
  186. // track_pose = submaps_.back()->track_pose;
  187. // __optimization(point_cloud, track_pose, global_pose);
  188. #endif
  189. }
  190. else {
  191. odom_pose_.pose = global_pose;
  192. }
  193. #if POSEGRAPH2
  194. if (!submaps_.empty()) {
  195. track_pose = submaps_.back()->track_pose;
  196. }
  197. #endif
  198. if (submaps_.empty() || __frameParallaxAchieve(track_pose, achieve_range_, achieve_angle_) || compir_success) {
  199. __createNewSubmap(point_cloud, global_pose, track_pose);
  200. track_pose = common::Rigid2f({0.0, 0.0}, 0.0);
  201. __buildSubmap(track_pose);
  202. submaps_.back()->track_pose = track_pose;
  203. }
  204. else {
  205. submaps_.back()->track_pose = track_pose;// = submaps_.back()->global_pose.inverse() * global_pose;
  206. __buildSubmap(track_pose);
  207. }
  208. #if 0
  209. global_map_->clearShadowMap();
  210. for (std::shared_ptr<SubMap>& submap : submaps_) {
  211. common::PointCloud global_point_cloud = __transformPointCloud(submap->point_cloud, submap->global_pose);
  212. common::PointCloud result = filter::VoxelInterpolationFilter(global_point_cloud, global_map_->getResolution());
  213. global_map_->pixelValuePlusShadow(result.data, probability_plus_, probability_up_);
  214. }
  215. #else
  216. {
  217. __globalMapBeamMode(global_pose);
  218. __growGlobalmap(global_pose);
  219. }
  220. #endif
  221. #if 1
  222. {
  223. static int i = 0;
  224. i++;
  225. if (i > 10) {
  226. global_map_->out("/home/space/catkin_ws/100.png");
  227. submaps_.back()->map->out("/home/space/catkin_ws/101.png");
  228. i = 0;
  229. }
  230. }
  231. #endif
  232. __writeTimePose({global_pose, std::chrono::system_clock::now(),
  233. global_map_->getCost(__transformPointCloud(point_cloud, global_pose))});
  234. #if POSEGRAPH2
  235. if (submaps_.size() > 1) {
  236. #else
  237. if (submaps_.size() > window_size_) {
  238. #endif
  239. submaps_.pop_front();
  240. return;
  241. }
  242. return;
  243. }
  244. void Slam::__buildSubmap(common::Rigid2f pose)
  245. {
  246. common::PointCloud point_cloud = __transformScanData2PointCloudError(0.0);
  247. common::PointCloud word = __transformPointCloud(point_cloud, pose);
  248. common::PointCloud result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  249. submaps_.back()->map->pixelValuePlus2(result.data, 1.0, 1.0);
  250. point_cloud = __transformScanData2PointCloudError(submaps_.back()->map->getResolution());
  251. word = __transformPointCloud(point_cloud, pose);
  252. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  253. submaps_.back()->map->pixelValuePlus2(result.data, 0.5, 1.0);
  254. point_cloud = __transformScanData2PointCloudError(-submaps_.back()->map->getResolution());
  255. word = __transformPointCloud(point_cloud, pose);
  256. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  257. submaps_.back()->map->pixelValuePlus2(result.data, 0.5, 1.0);
  258. point_cloud = __transformScanData2PointCloudError(2.0 * submaps_.back()->map->getResolution());
  259. word = __transformPointCloud(point_cloud, pose);
  260. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  261. submaps_.back()->map->pixelValuePlus2(result.data, 0.25, 1.0);
  262. point_cloud = __transformScanData2PointCloudError(-2.0 * submaps_.back()->map->getResolution());
  263. word = __transformPointCloud(point_cloud, pose);
  264. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  265. submaps_.back()->map->pixelValuePlus2(result.data, 0.25, 1.0);
  266. point_cloud = __transformScanData2PointCloudError(3.0 * submaps_.back()->map->getResolution());
  267. word = __transformPointCloud(point_cloud, pose);
  268. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  269. submaps_.back()->map->pixelValuePlus2(result.data, 0.12, 1.0);
  270. point_cloud = __transformScanData2PointCloudError(-3.0 * submaps_.back()->map->getResolution());
  271. word = __transformPointCloud(point_cloud, pose);
  272. result = filter::MapVoxelInterpolationFilter(word, *submaps_.back()->map, submaps_.back()->map->getResolution());
  273. submaps_.back()->map->pixelValuePlus2(result.data, 0.12, 1.0);
  274. submaps_.back()->track_pose = pose;
  275. }
  276. void Slam::__growGlobalmap(common::Rigid2f pose)
  277. {
  278. common::PointCloud point_cloud = __transformScanData2PointCloudError(0.0);
  279. common::PointCloud global_point_cloud = __transformPointCloud(point_cloud, pose);
  280. common::PointCloud result = filter::MapVoxelInterpolationFilter(global_point_cloud, *global_map_, global_map_->getResolution());
  281. global_map_->pixelValuePlus3(global_point_cloud.data, probability_plus_, probability_up_);
  282. point_cloud = __transformScanData2PointCloudError(global_map_->getResolution());
  283. global_point_cloud = __transformPointCloud(point_cloud, pose);
  284. result = filter::MapVoxelInterpolationFilter(global_point_cloud, *global_map_, global_map_->getResolution());
  285. global_map_->pixelValuePlus3(global_point_cloud.data, probability_plus_ * 0.5, probability_up_* 0.5);
  286. point_cloud = __transformScanData2PointCloudError(-global_map_->getResolution());
  287. global_point_cloud = __transformPointCloud(point_cloud, pose);
  288. result = filter::MapVoxelInterpolationFilter(global_point_cloud, *global_map_, global_map_->getResolution());
  289. global_map_->pixelValuePlus3(global_point_cloud.data, probability_plus_* 0.5, probability_up_* 0.5);
  290. point_cloud = __transformScanData2PointCloudError(2.0 * global_map_->getResolution());
  291. global_point_cloud = __transformPointCloud(point_cloud, pose);
  292. result = filter::MapVoxelInterpolationFilter(point_cloud, *global_map_, global_map_->getResolution());
  293. global_map_->pixelValuePlus3(global_point_cloud.data, probability_plus_ * 0.25, probability_up_* 0.25);
  294. point_cloud = __transformScanData2PointCloudError(-2.0 * global_map_->getResolution());
  295. global_point_cloud = __transformPointCloud(point_cloud, pose);
  296. result = filter::MapVoxelInterpolationFilter(global_point_cloud, *global_map_, global_map_->getResolution());
  297. global_map_->pixelValuePlus3(global_point_cloud.data, probability_plus_* 0.25, probability_up_* 0.25);
  298. }
  299. void Slam::__optimization(common::PointCloud& point_cloud, common::Rigid2f& track_pose, common::Rigid2f& global_pose)
  300. {
  301. if (submaps_.empty()) {
  302. return;
  303. }
  304. static common::Time clock = std::chrono::system_clock::now();
  305. common::Rigid2f perticet = submaps_.back()->track_pose;
  306. float a = 0.05;
  307. float b = 0.1;
  308. track_pose = __Match(perticet, point_cloud, *submaps_.back()->map, a, b);
  309. // if (!global_map_->empty()) {
  310. global_pose = __Match(global_pose, point_cloud, *global_map_, search_range_, search_angle_);
  311. // }
  312. clock = std::chrono::system_clock::now();
  313. // pose_graph
  314. double vertex_translation[submaps_.size() + 1][3];
  315. double vertex_rotation[submaps_.size() + 1][4];
  316. double edge_translation[submaps_.size() + 1][3];
  317. double edge_rotation[submaps_.size() + 1][4];
  318. for (int i = 0;i < submaps_.size() + 1;i++) {
  319. if (i < submaps_.size()) {
  320. __Rigid2fTranslation2Double3(submaps_[i]->global_pose, vertex_translation[i]);
  321. __Rigid2fQuaterniond2Double4(submaps_[i]->global_pose, vertex_rotation[i]);
  322. if (submaps_[i]->next != nullptr) {
  323. __Rigid2fTranslation2Double3(submaps_[i]->next->transform, edge_translation[i]);
  324. __Rigid2fQuaterniond2Double4(submaps_[i]->next->transform, edge_rotation[i]);
  325. }
  326. else {
  327. __Rigid2fTranslation2Double3(track_pose, edge_translation[i]);
  328. __Rigid2fQuaterniond2Double4(track_pose, edge_rotation[i]);
  329. }
  330. }
  331. else {
  332. __Rigid2fTranslation2Double3(global_pose, vertex_translation[i]);
  333. __Rigid2fQuaterniond2Double4(global_pose, vertex_rotation[i]);
  334. }
  335. }
  336. ceres::Solver::Summary summary;
  337. ceres::Problem problem;
  338. ceres::LossFunction *loss_function;
  339. loss_function = new ceres::CauchyLoss(1.0);
  340. pose_graph::PoseGraphFunction *cost_f = new pose_graph::PoseGraphFunction();
  341. // LOG(INFO)<<"submap size: "<<submaps_.size();
  342. // 添加后端约束
  343. for (int i = 0;i < submaps_.size();i++) {
  344. ceres::LocalParameterization *vertex_translation_i_parameterization = new pose_graph::TranslationLocalParameterization();
  345. problem.AddParameterBlock(vertex_translation[i], 3, vertex_translation_i_parameterization);
  346. ceres::LocalParameterization *vertex_rotation_i_parameterization = new pose_graph::QuaternionLocalParameterization();
  347. problem.AddParameterBlock(vertex_rotation[i], 4, vertex_rotation_i_parameterization);
  348. if (i == submaps_.size() - 1) {
  349. ceres::LocalParameterization *vertex_translation_ip_parameterization = new pose_graph::TranslationLocalParameterization();
  350. problem.AddParameterBlock(vertex_translation[submaps_.size()], 3, vertex_translation_ip_parameterization);
  351. ceres::LocalParameterization *vertex_rotation_ip_parameterization = new pose_graph::QuaternionLocalParameterization();
  352. problem.AddParameterBlock(vertex_rotation[submaps_.size()], 4, vertex_rotation_ip_parameterization);
  353. }
  354. ceres::LocalParameterization *edge_translation_i_parameterization = new pose_graph::TranslationLocalParameterization();
  355. problem.AddParameterBlock(edge_translation[i], 3, edge_translation_i_parameterization);
  356. ceres::LocalParameterization *edge_rotation_i_parameterization = new pose_graph::QuaternionLocalParameterization();
  357. problem.AddParameterBlock(edge_rotation[i], 4, edge_rotation_i_parameterization);
  358. if (i == 0) {
  359. problem.SetParameterBlockConstant(vertex_translation[0]);
  360. problem.SetParameterBlockConstant(vertex_rotation[0]);
  361. }
  362. // problem.AddResidualBlock(cost_f, loss_function, vertex_translation[i], vertex_rotation[i],
  363. // vertex_translation[i + 1], vertex_rotation[i + 1], edge_translation[i], edge_rotation[i]);
  364. }
  365. // 添加子地图约束
  366. {
  367. // 在之前的track pose的基础上使用惯性导航做预测
  368. // 用里程计做初步推算
  369. Eigen::Vector2d traget_translation = Eigen::Vector2d(track_pose.translation()(0), track_pose.translation()(1));
  370. double p4[4];
  371. __Rigid2fQuaterniond2Double4(track_pose, p4);
  372. problem.AddResidualBlock(
  373. CreateOccupiedSpaceCostFunction(
  374. 1.0 / std::sqrt(static_cast<double>(point_cloud.data.size())),
  375. point_cloud, *submaps_.back()->map),
  376. nullptr /* loss function */, edge_translation[submaps_.size() - 1], edge_rotation[submaps_.size() - 1]);
  377. problem.AddResidualBlock(
  378. TranslationDeltaCostFunctor::CreateAutoDiffCostFunction(
  379. 2.0, traget_translation), //10.0
  380. nullptr /* loss function */, edge_translation[submaps_.size() - 1]);
  381. ceres_matching::RotationDeltaCostFunctor* self_rotation_costfun =
  382. new ceres_matching::RotationDeltaCostFunctor(3.0, edge_rotation[submaps_.size() - 1]);
  383. problem.AddResidualBlock(self_rotation_costfun, // 40.0
  384. nullptr /* loss function */, edge_rotation[submaps_.size() - 1]); // 稳定残差
  385. ceres_matching::RotationDeltaCostFunctor* traget_rotation_costfun =
  386. new ceres_matching::RotationDeltaCostFunctor(3.0, p4);
  387. problem.AddResidualBlock(traget_rotation_costfun, // 6.0
  388. nullptr /* loss function */, edge_rotation[submaps_.size() - 1]);
  389. }
  390. // 添加全局地图约束
  391. // if (!global_map_->empty()) {
  392. // 在之前的track pose的基础上使用惯性导航做预测
  393. // 用里程计做初步推算
  394. Eigen::Vector2d traget_translation = Eigen::Vector2d(global_pose.translation()(0), global_pose.translation()(1));
  395. double p4[4];
  396. __Rigid2fQuaterniond2Double4(global_pose, p4);
  397. problem.AddResidualBlock(
  398. CreateOccupiedSpaceCostFunction(
  399. 1.0 / std::sqrt(static_cast<double>(point_cloud.data.size())),
  400. point_cloud, *global_map_),
  401. nullptr /* loss function */, vertex_translation[submaps_.size()], vertex_rotation[submaps_.size()]);
  402. problem.AddResidualBlock(
  403. TranslationDeltaCostFunctor::CreateAutoDiffCostFunction(
  404. 2.0, traget_translation), //10.0
  405. nullptr /* loss function */, vertex_translation[submaps_.size()]);
  406. ceres_matching::RotationDeltaCostFunctor* self_rotation_costfun =
  407. new ceres_matching::RotationDeltaCostFunctor(3.0, vertex_rotation[submaps_.size()]);
  408. problem.AddResidualBlock(self_rotation_costfun, // 40.0
  409. nullptr /* loss function */, vertex_rotation[submaps_.size()]); // 稳定残差
  410. ceres_matching::RotationDeltaCostFunctor* traget_rotation_costfun =
  411. new ceres_matching::RotationDeltaCostFunctor(1.0, p4);
  412. problem.AddResidualBlock(traget_rotation_costfun, // 6.0
  413. nullptr /* loss function */, vertex_rotation[submaps_.size()]);
  414. // }
  415. // 添加里程计约束
  416. // {
  417. // common::Rigid2f odom;
  418. // double odom_translation[3] = {0};
  419. // double odom_rotation[4] = {0};
  420. // static common::Time clock = std::chrono::system_clock::now();
  421. // odom_->extrapolaOdom(clock, std::chrono::system_clock::now(), odom);
  422. // __Rigid2fTranslation2Double3(odom, odom_translation);
  423. // __Rigid2fQuaterniond2Double4(odom, odom_rotation);
  424. // ceres::LocalParameterization *edges_o_translation_parameterization = new pose_graph::TranslationLocalParameterization();
  425. // problem.AddParameterBlock(odom_translation, 3, edges_o_translation_parameterization);
  426. // problem.SetParameterBlockConstant(odom_translation);
  427. // ceres::LocalParameterization *edges_o_rotation_parameterization = new pose_graph::QuaternionLocalParameterization();
  428. // problem.AddParameterBlock(odom_rotation, 4, edges_o_rotation_parameterization);
  429. // problem.SetParameterBlockConstant(odom_rotation);
  430. // problem.AddResidualBlock(cost_f, loss_function, vertex_translation[submaps_.size() - 1],
  431. // vertex_rotation[submaps_.size() - 1], vertex_translation[submaps_.size()], vertex_rotation[submaps_.size()],
  432. // odom_translation, odom_rotation);
  433. // }
  434. ceres::Solver::Options options;
  435. options.linear_solver_type = ceres::DENSE_SCHUR;
  436. options.trust_region_strategy_type = ceres::DOGLEG;
  437. options.max_num_iterations = 50;
  438. ceres::Solve(options, &problem, &summary);
  439. for (int i = 0;i < submaps_.size();i++) {
  440. __double34ToRigid2f(vertex_translation[i], vertex_rotation[i], submaps_[i]->global_pose);
  441. if (submaps_[i]->next != nullptr) {
  442. __double34ToRigid2f(edge_translation[i], edge_rotation[i], submaps_[i]->next->transform);
  443. }
  444. }
  445. __double34ToRigid2f(edge_translation[submaps_.size() - 1], edge_rotation[submaps_.size() - 1], track_pose);
  446. // __double34ToRigid2f(vertex_translation[submaps_.size()], vertex_rotation[submaps_.size()], global_pose);
  447. }
  448. // 更新submap的global pose和edge,计算当前最佳的global pose
  449. void Slam::__poseGraph(common::Rigid2f& global_pose, common::Rigid2f& track_pose)
  450. {
  451. double vertexs[submaps_.size() + 1][7];
  452. double edges[submaps_.size() + 1][7];
  453. for (int i = 0;i < submaps_.size() + 1;i++) {
  454. if (i < submaps_.size()) {
  455. __Rigid2f2Double7(submaps_[i]->global_pose, vertexs[i]);
  456. if (submaps_[i]->next != nullptr) {
  457. __Rigid2f2Double7(submaps_[i]->next->transform, edges[i]);
  458. }
  459. else {
  460. __Rigid2f2Double7(track_pose, edges[i]);
  461. }
  462. } // i == submap size 把当前帧的全局匹配位姿作为最后一个顶点
  463. else {
  464. __Rigid2f2Double7(global_pose, vertexs[i]);
  465. }
  466. }
  467. ceres::Solver::Summary summary;
  468. ceres::Problem problem;
  469. ceres::LossFunction *loss_function;
  470. loss_function = new ceres::CauchyLoss(1.0);
  471. // LOG(INFO)<<"submap size: "<<submaps_.size();
  472. for (int i = 0;i < submaps_.size();i++) {
  473. pose_graph::PoseCostFunction *cost_f = new pose_graph::PoseCostFunction();
  474. ceres::LocalParameterization *vertexs_i_parameterization = new pose_graph::PoseLocalParameterization();
  475. problem.AddParameterBlock(vertexs[i], 7, vertexs_i_parameterization);
  476. if (i == submaps_.size() - 1) {
  477. ceres::LocalParameterization *vertexs_ip_parameterization = new pose_graph::PoseLocalParameterization();
  478. problem.AddParameterBlock(vertexs[i + 1], 7, vertexs_ip_parameterization);
  479. problem.SetParameterBlockConstant(vertexs[i + 1]);
  480. }
  481. // else {
  482. // problem.SetParameterBlockConstant(vertexs[i]);
  483. // }
  484. ceres::LocalParameterization *edges_i_parameterization = new pose_graph::PoseLocalParameterization();
  485. problem.AddParameterBlock(edges[i], 7, edges_i_parameterization);
  486. // problem.SetParameterBlockConstant(edges[i]);
  487. if (i == 0) { // 将第0帧固定,不进行优化
  488. problem.SetParameterBlockConstant(vertexs[0]);
  489. problem.SetParameterBlockConstant(edges[0]);
  490. }
  491. problem.AddResidualBlock(cost_f, loss_function, vertexs[i], vertexs[i + 1], edges[i]);
  492. }
  493. ceres::Solver::Options options;
  494. options.linear_solver_type = ceres::DENSE_SCHUR;
  495. options.trust_region_strategy_type = ceres::DOGLEG;
  496. options.max_num_iterations = 50;
  497. ceres::Solve(options, &problem, &summary);
  498. for (int i = 0;i < submaps_.size();i++) {
  499. __double7ToRigid2f(vertexs[i], submaps_[i]->global_pose);
  500. if (submaps_[i]->next != nullptr) {
  501. __double7ToRigid2f(edges[i], submaps_[i]->next->transform);
  502. }
  503. }
  504. __double7ToRigid2f(vertexs[submaps_.size()], global_pose);
  505. __double7ToRigid2f(edges[submaps_.size() - 1], track_pose);
  506. }
  507. // 更新submap的global pose和edge,计算当前最佳的global pose
  508. void Slam::__poseGraph2(common::Rigid2f& global_pose)
  509. {
  510. if (submaps_.empty()) {
  511. return;
  512. }
  513. double vertexs[submaps_.size() + 1][7];
  514. double edges[submaps_.size() + 1][7];
  515. double hyp_edges[submaps_.size() + 1][7];
  516. ceres::Solver::Summary summary;
  517. ceres::Problem problem;
  518. ceres::LossFunction *loss_function;
  519. loss_function = new ceres::CauchyLoss(1.0);
  520. __Rigid2f2Double7(global_pose, vertexs[submaps_.size()]);
  521. ceres::LocalParameterization *local_parameterization = new pose_graph::PoseLocalParameterization();
  522. problem.AddParameterBlock(vertexs[submaps_.size()], 7, local_parameterization);
  523. for (int i = 0;i < submaps_.size();i++) {
  524. pose_graph::PoseCostFunction *cost_f = new pose_graph::PoseCostFunction();
  525. __Rigid2f2Double7(submaps_[i]->global_pose, vertexs[i]);
  526. __Rigid2f2Double7(submaps_[i]->track_pose, edges[i]);
  527. ceres::LocalParameterization *global_pose_local_parameterization = new pose_graph::PoseLocalParameterization();
  528. problem.AddParameterBlock(vertexs[i], 7, global_pose_local_parameterization);
  529. ceres::LocalParameterization *track_pose_local_parameterization = new pose_graph::PoseLocalParameterization();
  530. problem.AddParameterBlock(edges[i], 7, track_pose_local_parameterization);
  531. if (i < submaps_.size() - 1) {
  532. __Rigid2f2Double7(submaps_[i]->next->transform, hyp_edges[i]);
  533. ceres::LocalParameterization *hyp_edges_local_parameterization = new pose_graph::PoseLocalParameterization();
  534. problem.AddParameterBlock(hyp_edges[i], 7, hyp_edges_local_parameterization);
  535. problem.AddResidualBlock(cost_f, loss_function, vertexs[i], vertexs[i + 1], hyp_edges[i]);
  536. if (i == 0) {
  537. problem.SetParameterBlockConstant(hyp_edges[0]);
  538. }
  539. }
  540. if (i == 0) { // 将第0帧固定,不进行优化
  541. problem.SetParameterBlockConstant(vertexs[0]);
  542. problem.SetParameterBlockConstant(edges[0]);
  543. }
  544. problem.AddResidualBlock(cost_f, loss_function, vertexs[i], vertexs[submaps_.size()], edges[i]);
  545. }
  546. ceres::Solver::Options options;
  547. options.linear_solver_type = ceres::DENSE_SCHUR;
  548. options.trust_region_strategy_type = ceres::DOGLEG;
  549. options.max_num_iterations = 50;
  550. ceres::Solve(options, &problem, &summary);
  551. for (int i = 0;i < submaps_.size();i++) {
  552. __double7ToRigid2f(vertexs[i], submaps_[i]->global_pose);
  553. __double7ToRigid2f(edges[i], submaps_[i]->track_pose);
  554. if (submaps_[i]->next != nullptr) {
  555. __double7ToRigid2f(hyp_edges[i], submaps_[i]->next->transform);
  556. }
  557. }
  558. __double7ToRigid2f(vertexs[submaps_.size()], global_pose);
  559. }
  560. common::Rigid2f Slam::__Match(common::Rigid2f& pose,
  561. common::PointCloud& point_cloud,
  562. Map& map,
  563. const float& range,
  564. const float& rad,
  565. const float occupied_space_weight,
  566. const float translation_weight,
  567. const float rotation_weight,
  568. const float self_stab_weight)
  569. {
  570. RealTimeMatch2D matcher;
  571. common::Rigid2f real_time_match_pose, predict_pose, ceres_match_pose, odom;
  572. ceres::Solver::Summary summary;
  573. float cost = 0;
  574. common::PointCloud filter = filter::VoxelInterpolationFilter(point_cloud, 0.1);
  575. // common::PointCloud filter = __transformScanData2PointCloudError(0.0, 0.0085);
  576. predict_pose = pose;
  577. matcher.setSearchRange(range, rad, map.getResolution());
  578. if (use_towermatch_) {
  579. cost = matcher.towerMatch(filter, predict_pose, real_time_match_pose, map, 2.0);
  580. }
  581. else {
  582. cost = matcher.match(filter, predict_pose, real_time_match_pose, map);
  583. }
  584. if (cost < 1e-2) {
  585. real_time_match_pose = predict_pose;
  586. }
  587. CeresScanMatcher2D ceres_scan_matcher(occupied_space_weight, translation_weight, rotation_weight, self_stab_weight);
  588. ceres_scan_matcher.Match(real_time_match_pose, real_time_match_pose, point_cloud, map, &ceres_match_pose, &summary);
  589. common::PointCloud opt_cloud = __transformPointCloud(point_cloud, ceres_match_pose);
  590. std::vector<common::PointCloud> group;
  591. common::PointCloud element;
  592. // 分组
  593. for (int i = 0;i < opt_cloud.data.size();i++) {
  594. if (!element.data.empty()) {
  595. float dist = hypot(element.data.back()(0) - opt_cloud.data[i](0),
  596. element.data.back()(1) - opt_cloud.data[i](1));
  597. if (dist > 0.2 || i == opt_cloud.data.size() - 1) {
  598. group.push_back(element);
  599. element.data.clear();
  600. }
  601. }
  602. element.data.push_back(opt_cloud.data[i]);
  603. }
  604. element.data.clear();
  605. for (common::PointCloud& cloud : group) {
  606. float cost = map.getCost(cloud);
  607. if (cloud.data.size() > 2 && cost > 0.1) {
  608. element.data.insert(element.data.end(), cloud.data.begin(), cloud.data.end());
  609. }
  610. }
  611. element = __transformPointCloud(element, ceres_match_pose.inverse());
  612. common::Rigid2f pr;
  613. CeresScanMatcher2D ceres_scan_matcher2(occupied_space_weight, translation_weight, rotation_weight, self_stab_weight);
  614. ceres_scan_matcher2.Match(ceres_match_pose, ceres_match_pose, element, map, &pr, &summary);
  615. return pr;
  616. // return ceres_match_pose;
  617. }
  618. common::PointCloud Slam::__transformPointCloud(
  619. const common::PointCloud& point_cloud, const common::Rigid2f& transform)
  620. {
  621. common::PointCloud trans_cloud;
  622. trans_cloud.data.resize(point_cloud.data.size());
  623. for (int i = 0;i < point_cloud.data.size();i++) {
  624. Eigen::Vector3f trans;
  625. common::Rigid2f::Vector vector = point_cloud.data[i].head<2>();
  626. vector = transform * vector;
  627. trans = Eigen::Vector3f(vector(0), vector(1), 0.0);
  628. trans_cloud.data[i] = trans;
  629. }
  630. trans_cloud.time = point_cloud.time;
  631. return trans_cloud;
  632. }
  633. void Slam::__writeTimePose(common::TimeRigid2f time_pose)
  634. {
  635. TIME_POSE_LOCK()
  636. time_pose_ = time_pose;
  637. }
  638. void Slam::__createNewSubmap(common::PointCloud& point_cloud, common::Rigid2f& global_pose, common::Rigid2f& track_pose)
  639. {
  640. std::shared_ptr<SubMap> ptr = std::shared_ptr<SubMap>(new SubMap(submap_size_, submap_resolution_));
  641. std::shared_ptr<con> con_ptr = std::shared_ptr<con>(new con());
  642. ptr->global_pose = global_pose;
  643. if (!submaps_.empty()) {
  644. con_ptr->submap = ptr;
  645. con_ptr->transform = track_pose;
  646. submaps_.back()->next = con_ptr; // 把上一个submap的next指向最新的submap
  647. }
  648. submaps_.push_back(ptr);
  649. submaps_.back()->point_cloud = point_cloud;
  650. // __buildSubmap(common::Rigid2f({0.0, 0.0}, 0.0));
  651. // submaps_.back()->track_pose = common::Rigid2f({0.0, 0.0}, 0.0);
  652. }
  653. void Slam::__Rigid2f2Double7(common::Rigid2f& rigid2f, double* d7)
  654. {
  655. d7[0] = rigid2f.translation()(0);
  656. d7[1] = rigid2f.translation()(1);
  657. d7[2] = 0.0;
  658. Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(0, Eigen::Vector3d::UnitX()));
  659. Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(0, Eigen::Vector3d::UnitY()));
  660. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(rigid2f.rotation().angle(), Eigen::Vector3d::UnitZ()));
  661. Eigen::Quaterniond quaternion;
  662. quaternion = yawAngle * pitchAngle * rollAngle;
  663. d7[3] = quaternion.x();
  664. d7[4] = quaternion.y();
  665. d7[5] = quaternion.z();
  666. d7[6] = quaternion.w();
  667. }
  668. void Slam::__double7ToRigid2f(double* d7, common::Rigid2f& rigid2f)
  669. {
  670. Eigen::Quaterniond q(d7[6], d7[3], d7[4], d7[5]);
  671. q.normalized();
  672. rigid2f = common::Rigid2f({d7[0], d7[1]}, q.matrix().eulerAngles(0, 1, 2)(2));
  673. }
  674. void Slam::__Rigid2fTranslation2Double3(common::Rigid2f& rigid2f, double* d3)
  675. {
  676. d3[0] = rigid2f.translation()(0);
  677. d3[1] = rigid2f.translation()(1);
  678. d3[2] = rigid2f.translation()(2);
  679. }
  680. void Slam::__Rigid2fQuaterniond2Double4(common::Rigid2f& rigid2f, double* d4)
  681. {
  682. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(rigid2f.rotation().angle(), Eigen::Vector3d::UnitZ()));
  683. Eigen::Quaterniond quaternion;
  684. quaternion = yawAngle;// * pitchAngle * rollAngle;
  685. d4[0] = quaternion.x();
  686. d4[1] = quaternion.y();
  687. d4[2] = quaternion.z();
  688. d4[3] = quaternion.w();
  689. }
  690. void Slam::__double34ToRigid2f(double* d3, double* d4, common::Rigid2f& rigid2f)
  691. {
  692. Eigen::Quaterniond q(d4[3], d4[0], d4[1], d4[2]);
  693. rigid2f = common::Rigid2f({d3[0], d3[1]}, q.matrix().eulerAngles(0, 1, 2)(2));
  694. }
  695. bool Slam::__frameParallaxAchieve(common::Rigid2f& pose, float achieve_range, float achieve_angle)
  696. {
  697. if (pose.translation().norm() > achieve_range || fabs(pose.rotation().angle()) > achieve_angle) {
  698. return true;
  699. }
  700. return false;
  701. }
  702. common::PointCloud Slam::__transformScanData2PointCloudError(float error, const float angle_increment)
  703. {
  704. common::PointCloud point_cloud;
  705. float theta = scan_.angle_max;
  706. float offset = scan_.angle_max + scan_.angle_min;
  707. float sum_angle = 0;
  708. for (float range : scan_.ranges) {
  709. theta -= scan_.angle_increment;
  710. sum_angle += scan_.angle_increment;
  711. if (sum_angle < angle_increment) continue;
  712. if (range > scan_.range_max) continue;
  713. if (range < scan_.range_min) continue;
  714. if (theta < scan_.angle_min) continue;
  715. if (theta > scan_.angle_max) continue;
  716. if (std::isnan(range)) continue;
  717. sum_angle = 0.;
  718. range += error;
  719. const Eigen::Matrix<float, 4, 1> point(range * cos(theta - offset),
  720. -range * sin(theta - offset),
  721. 0.0,
  722. 1.0);
  723. //将基于传感器坐标系的数据转到基于base_link坐标系
  724. Eigen::Matrix<float, 4, 1> base = laser_tf_ * point;
  725. point_cloud.data.push_back(
  726. Eigen::Vector3f(base(0), base(1), base(2))
  727. );
  728. }
  729. point_cloud.time = std::chrono::system_clock::now();
  730. return point_cloud;
  731. }
  732. void Slam::__globalMapBeamMode(common::Rigid2f& global_tf)
  733. {
  734. common::PointCloud point_cloud;
  735. float theta = scan_.angle_max;
  736. float offset = scan_.angle_max + scan_.angle_min;
  737. float r2 = global_map_->getResolution() * global_map_->getResolution() * 2.0;
  738. r2 = sqrt(r2) * 4.0;
  739. for (float range : scan_.ranges) {
  740. theta -= scan_.angle_increment;
  741. if (range > scan_.range_max) continue;
  742. if (range < scan_.range_min) continue;
  743. if (theta < scan_.angle_min) continue;
  744. if (theta > scan_.angle_max) continue;
  745. if (std::isnan(range)) continue;
  746. float start = range - r2;
  747. if (start < 0) {
  748. continue;
  749. }
  750. const Eigen::Matrix<float, 4, 1> point(start * cos(theta - offset),
  751. -start * sin(theta - offset),
  752. 0.0,
  753. 1.0);
  754. //将基于传感器坐标系的数据转到基于base_link坐标系
  755. Eigen::Matrix<float, 4, 1> base = laser_tf_ * point;
  756. common::Rigid2f::Vector vector(base(0), base(1));
  757. common::Rigid2f::Vector laser_trans(laser_tf_(0, 3), laser_tf_(1, 3));
  758. vector = global_tf * vector;
  759. laser_trans = global_tf * laser_trans;
  760. float x = -laser_trans(0) + vector(0);
  761. float y = -laser_trans(1) + vector(1);
  762. float step = std::max(fabs(x) / global_map_->getResolution(), fabs(y) / global_map_->getResolution());
  763. float step_x = x / step;
  764. float step_y = y / step;
  765. x = laser_trans(0), y = laser_trans(1);
  766. for (float error = 0.0;error < step + 1.0;error += 1.0) {
  767. x += step_x;
  768. y += step_y;
  769. global_map_->weakenPixel(x, y, 0.001);
  770. }
  771. }
  772. }
  773. }
  774. }