wheel_detector.cpp 17 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398
  1. #include "wheel_detector.h"
  2. #include <ceres/ceres.h>
  3. #include <ceres/cubic_interpolation.h>
  4. struct singleWheelCostFunction {
  5. std::vector<float> line_;
  6. pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_;
  7. Eigen::Vector4f centroid;
  8. explicit singleWheelCostFunction(const std::vector<float> &line, pcl::PointCloud<pcl::PointXYZ>::Ptr cloud) {
  9. line_ = line;
  10. cloud_ = cloud;
  11. pcl::compute3DCentroid(*cloud, centroid);
  12. }
  13. template<typename JetT>
  14. bool operator()(const JetT *const x, JetT *residual) const {
  15. ceres::Grid1D<float> grid(line_.data(), 0, line_.size());
  16. ceres::CubicInterpolator<ceres::Grid1D<float>> cubic(grid);
  17. JetT delta_x = x[0] + JetT(centroid.x() + 2);
  18. JetT theta = x[1];
  19. auto cos_t = ceres::cos(theta);
  20. auto sin_t = ceres::sin(theta);
  21. for (int i = 0; i < cloud_->size(); ++i) {
  22. JetT cx = JetT(cloud_->points[i].x - centroid.x()) * cos_t - JetT(cloud_->points[i].y - centroid.y()) * sin_t + delta_x;
  23. cubic.Evaluate(cx * 1000.,&residual[i]);
  24. residual[i]=JetT(1.0)-residual[i];
  25. }
  26. return true;
  27. }
  28. };
  29. struct doubleWheelCostFunction {
  30. std::vector<float> line_l_;
  31. std::vector<float> line_r_;
  32. pcl::PointCloud<pcl::PointXYZ>::Ptr m_left_cloud;
  33. pcl::PointCloud<pcl::PointXYZ>::Ptr m_right_cloud;
  34. explicit doubleWheelCostFunction(const std::vector<float> &linel,const std::vector<float> &liner, pcl::PointCloud<pcl::PointXYZ>::Ptr left_cloud, pcl::PointCloud<pcl::PointXYZ>::Ptr right_cloud) {
  35. line_l_ = linel;
  36. line_r_ = liner;
  37. m_left_cloud = left_cloud;
  38. m_right_cloud = right_cloud;
  39. }
  40. template<typename JetT>
  41. bool operator()(const JetT *const x, JetT *residual) const {
  42. ceres::Grid1D<float> gridl(line_l_.data(), 0, line_l_.size());
  43. ceres::CubicInterpolator<ceres::Grid1D<float>> cubicl(gridl);
  44. ceres::Grid1D<float> gridr(line_r_.data(), 0, line_r_.size());
  45. ceres::CubicInterpolator<ceres::Grid1D<float>> cubicr(gridr);
  46. JetT theta = x[0];
  47. JetT w = x[1];
  48. JetT tx = x[2];
  49. auto cos_t = ceres::cos(theta);
  50. auto sin_t = ceres::sin(theta);
  51. int resi_index = 0;
  52. for (auto &point: m_left_cloud->points) {
  53. JetT x=JetT(point.x);
  54. JetT y=JetT(point.y);
  55. JetT cx = x * cos_t - y * sin_t +tx + w*0.5;
  56. cubicl.Evaluate((cx +JetT(0.5)) * 1000.,&residual[resi_index]);
  57. residual[resi_index]=JetT(1.0)-residual[resi_index];
  58. resi_index++;
  59. }
  60. for (auto &point: m_right_cloud->points) {
  61. JetT x=JetT(point.x);
  62. JetT y=JetT(point.y);
  63. JetT cx = x * cos_t - y * sin_t + tx - w*0.5;
  64. cubicr.Evaluate((cx +JetT(2.0))* 1000.,&residual[resi_index]);
  65. residual[resi_index]=JetT(1.0)-residual[resi_index];
  66. resi_index++;
  67. }
  68. return true;
  69. }
  70. };
  71. struct WheelsTogetherCostFunction {
  72. std::vector<Eigen::Vector4f> m_vct_centroid;
  73. std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> m_vct_cloud;
  74. std::vector<ceres::CubicInterpolator<ceres::Grid1D<float>>*> m_vct_model;
  75. explicit WheelsTogetherCostFunction(std::vector<ceres::CubicInterpolator<ceres::Grid1D<float>>*> vct_model, std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> &vct_cloud, std::vector<Eigen::Vector4f> &vct_centroid) {
  76. m_vct_cloud = vct_cloud;
  77. m_vct_model = vct_model;
  78. m_vct_centroid = vct_centroid;
  79. }
  80. template<typename JetT>
  81. bool operator()(const JetT *const x, JetT *residual) const {
  82. int residual_index = 0;
  83. JetT delta_x[4] = {x[0] + JetT(m_vct_centroid[0].x() + 2), x[2] + JetT(m_vct_centroid[1].x() + 2), x[4] + JetT(m_vct_centroid[2].x() + 2), x[6] + JetT(m_vct_centroid[3].x() + 2)};
  84. JetT theta[4] = {x[1], x[3], x[5], x[7]};
  85. JetT cos_t[4] = {ceres::cos(theta[0]), ceres::cos(theta[1]), ceres::cos(theta[2]), ceres::cos(theta[3])};
  86. JetT sin_t[4] = {ceres::sin(theta[0]), ceres::cos(theta[1]), ceres::cos(theta[2]), ceres::cos(theta[3])};
  87. for (int device_index = 0; device_index < 4; device_index++) {
  88. for (auto &point: m_vct_cloud[device_index]->points) {
  89. JetT cx = JetT(point.x - m_vct_centroid[device_index].x()) * cos_t[device_index] - JetT(point.y - m_vct_centroid[device_index].y()) * sin_t[device_index] + delta_x[device_index];
  90. m_vct_model[device_index]->Evaluate(cx * 1000.,&residual[residual_index]);
  91. residual[residual_index]=JetT(1.0)-residual[residual_index];
  92. residual_index++;
  93. }
  94. }
  95. return true;
  96. }
  97. };
  98. bool WheelCeresDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr in_cloud_ptr,
  99. pcl::PointCloud<pcl::PointXYZ>::Ptr out_cloud_ptr,
  100. WheelCeresDetector::WheelDetectResult &result, bool left_model) {
  101. Eigen::Vector4f centroid;
  102. pcl::compute3DCentroid(*in_cloud_ptr, centroid);
  103. double t_vars[2] = {-centroid.x(), 0};
  104. LOG(INFO) << "ceres detect init info: " << t_vars[0] << " " << t_vars[1];
  105. auto model = left_model ? singleLeftWheelModel() : singleRightWheelModel();
  106. // 构建最小二乘问题
  107. ceres::Problem problem;
  108. problem.AddResidualBlock(new ceres::AutoDiffCostFunction<singleWheelCostFunction, ceres::DYNAMIC, 2>(
  109. (new singleWheelCostFunction(model, in_cloud_ptr)), in_cloud_ptr->size()),
  110. nullptr, // 核函数,这里不使用,为空
  111. t_vars // 待估计参数
  112. );
  113. // problem.SetParameterLowerBound(t_vars, 1, (-20) * M_PI / 180.0f);
  114. // problem.SetParameterUpperBound(t_vars, 1, (20) * M_PI / 180.0f);
  115. // 配置求解器
  116. ceres::Solver::Options options; // 这里有很多配置项可以填
  117. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  118. options.minimizer_progress_to_stdout = false; // 输出到cout
  119. options.max_num_iterations = 100;
  120. ceres::Solver::Summary summary; // 优化信息
  121. ceres::Solve(options, &problem, &summary); // 开始优化
  122. if(summary.iterations.size()<=1){
  123. LOG(INFO) << "仅迭代一轮,优化异常";
  124. return false;
  125. }
  126. if(summary.iterations[summary.iterations.size()-1].iteration<=1){
  127. LOG(INFO) << "最终仅迭代一轮,优化异常";
  128. return false;
  129. }
  130. LOG(INFO) << "ceres solve total time: " << summary.total_time_in_seconds * 1000 << "ms";
  131. result.theta = t_vars[1] * 180.0f / M_PI;
  132. float sin_t = std::sin(t_vars[1]);
  133. float cos_t = std::cos(t_vars[1]);
  134. for (auto &point: in_cloud_ptr->points) {
  135. float x = (point.x - centroid.x()) * cos_t - (point.y - centroid.y()) * sin_t + t_vars[0] + centroid.x();
  136. float y = 1.0 / (1.0 + ceres::exp(-400 * (x + 0.03))) - 1.0 / (1.0 + ceres::exp(-400 * (x-0.025)));
  137. if (y > 0.7) {
  138. out_cloud_ptr->push_back(point);
  139. }
  140. }
  141. pcl::compute3DCentroid(*out_cloud_ptr, centroid);
  142. result.center.x = centroid.x();
  143. result.center.y = centroid.y();
  144. result.center.z = centroid.z();
  145. LOG(INFO) << "num: " << out_cloud_ptr->size() << " " << result.info();
  146. return true;
  147. }
  148. bool WheelCeresDetector::detect(pcl::PointCloud<pcl::PointXYZ>::Ptr left_in_cloud,
  149. pcl::PointCloud<pcl::PointXYZ>::Ptr left_out_cloud,
  150. WheelCeresDetector::WheelDetectResult &left_result,
  151. pcl::PointCloud<pcl::PointXYZ>::Ptr right_in_cloud,
  152. pcl::PointCloud<pcl::PointXYZ>::Ptr right_out_cloud,
  153. WheelCeresDetector::WheelDetectResult &right_result) {
  154. if (left_in_cloud->empty() && right_in_cloud->empty()) {
  155. return false;
  156. } else if (left_in_cloud->empty() && !right_in_cloud->empty()) {
  157. return detect(right_in_cloud, right_out_cloud, right_result, false);
  158. } else if (!left_in_cloud->empty() && right_in_cloud->empty()) {
  159. return detect(left_in_cloud, left_out_cloud, left_result, true);
  160. }
  161. double t_vars[3] = {0, 3, 0};
  162. std::vector<float> linel,liner;
  163. doubleWheelModel(linel,liner);
  164. // 构建最小二乘问题
  165. ceres::Problem problem;
  166. problem.AddResidualBlock(new ceres::AutoDiffCostFunction<doubleWheelCostFunction, ceres::DYNAMIC, 3>(
  167. (new doubleWheelCostFunction(linel,liner, left_in_cloud, right_in_cloud)), left_in_cloud->size() + right_in_cloud->size()),
  168. nullptr, // 核函数,这里不使用,为空
  169. t_vars // 待估计参数
  170. );
  171. // problem.SetParameterLowerBound(t_vars, 1, (-20) * M_PI / 180.0f);
  172. // problem.SetParameterUpperBound(t_vars, 1, (20) * M_PI / 180.0f);
  173. // 配置求解器
  174. ceres::Solver::Options options; // 这里有很多配置项可以填
  175. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  176. options.minimizer_progress_to_stdout = false; // 输出到cout
  177. options.max_num_iterations = 100;
  178. ceres::Solver::Summary summary; // 优化信息
  179. ceres::Solve(options, &problem, &summary); // 开始优化
  180. if(summary.iterations.size()<=1){
  181. LOG(INFO) << "仅迭代一轮,优化异常";
  182. return false;
  183. }
  184. if(summary.iterations[summary.iterations.size()-1].iteration<=1){
  185. LOG(INFO) << "最终仅迭代一轮,优化异常";
  186. return false;
  187. }
  188. LOG(INFO) << "ceres solve total time: " << summary.total_time_in_seconds * 1000 << "ms";
  189. left_result.theta = t_vars[0] * 180.0f / M_PI;
  190. right_result.theta = t_vars[0] * 180.0f / M_PI;
  191. LOG(INFO) << left_result.info();
  192. LOG(INFO) << t_vars[1] << " " << t_vars[2];
  193. float sin_t = std::sin(t_vars[0]);
  194. float cos_t = std::cos(t_vars[0]);
  195. for (auto &point: left_in_cloud->points) {
  196. left_out_cloud->emplace_back((point.x ) * cos_t - (point.y ) * sin_t + t_vars[2] + t_vars[1]/2,
  197. (point.x ) * sin_t + (point.y) * cos_t ,
  198. point.z);
  199. }
  200. for (auto &point: right_in_cloud->points) {
  201. right_out_cloud->emplace_back((point.x ) * cos_t - (point.y) * sin_t + t_vars[2] - t_vars[1]/2,
  202. (point.x) * sin_t + (point.y ) * cos_t,
  203. point.z);
  204. }
  205. return true;
  206. }
  207. bool WheelCeresDetector::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>::Ptr> vct_wheels_cloud,
  208. pcl::PointCloud<pcl::PointXYZ>::Ptr left_out_cloud,
  209. WheelCeresDetector::WheelDetectResult *wheels_result) {
  210. std::vector<Eigen::Vector4f> vct_centroid;
  211. size_t all_wheel_size = 0;
  212. for (auto &wheel_cloud: vct_wheels_cloud) {
  213. Eigen::Vector4f centroid;
  214. pcl::compute3DCentroid(*wheel_cloud, centroid);
  215. vct_centroid.push_back(centroid);
  216. all_wheel_size += wheel_cloud->size();
  217. }
  218. std::vector<ceres::CubicInterpolator<ceres::Grid1D<float>>*> vct_model;
  219. std::vector<float> left_model, right_model;
  220. left_model = singleLeftWheelModel();
  221. right_model = singleRightWheelModel();
  222. ceres::Grid1D<float> left_grid(left_model.data(), 0, left_model.size());
  223. ceres::Grid1D<float> right_grid(right_model.data(), 0, right_model.size());
  224. vct_model.push_back(new ceres::CubicInterpolator<ceres::Grid1D<float>>(left_grid));
  225. vct_model.push_back(new ceres::CubicInterpolator<ceres::Grid1D<float>>(right_grid));
  226. vct_model.push_back(new ceres::CubicInterpolator<ceres::Grid1D<float>>(left_grid));
  227. vct_model.push_back(new ceres::CubicInterpolator<ceres::Grid1D<float>>(right_grid));
  228. double t_vars[8] = {-vct_centroid[0].x(), 0, -vct_centroid[1].x(), 0, -vct_centroid[2].x(), 0, -vct_centroid[3].x(), 0};
  229. // 构建最小二乘问题
  230. ceres::Problem problem;
  231. problem.AddResidualBlock(new ceres::AutoDiffCostFunction<WheelsTogetherCostFunction, ceres::DYNAMIC, 8>(
  232. (new WheelsTogetherCostFunction(vct_model, vct_wheels_cloud, vct_centroid)), all_wheel_size),
  233. nullptr, // 核函数,这里不使用,为空
  234. t_vars // 待估计参数
  235. );
  236. // problem.SetParameterLowerBound(t_vars, 1, (-20) * M_PI / 180.0f);
  237. // problem.SetParameterUpperBound(t_vars, 1, (20) * M_PI / 180.0f);
  238. // 配置求解器
  239. ceres::Solver::Options options; // 这里有很多配置项可以填
  240. options.linear_solver_type = ceres::DENSE_QR; // 增量方程如何求解
  241. options.minimizer_progress_to_stdout = false; // 输出到cout
  242. options.max_num_iterations = 100;
  243. ceres::Solver::Summary summary; // 优化信息
  244. ceres::Solve(options, &problem, &summary); // 开始优化
  245. if(summary.iterations.size()<=1){
  246. LOG(INFO) << "仅迭代一轮,优化异常";
  247. return false;
  248. }
  249. if(summary.iterations[summary.iterations.size()-1].iteration<=1){
  250. LOG(INFO) << "最终仅迭代一轮,优化异常";
  251. return false;
  252. }
  253. LOG(INFO) << "ceres solve total time: " << summary.total_time_in_seconds * 1000 << "ms";
  254. wheels_result[0].theta = t_vars[0] * 180.0f / M_PI;
  255. wheels_result[1].theta = t_vars[2] * 180.0f / M_PI;
  256. wheels_result[2].theta = t_vars[4] * 180.0f / M_PI;
  257. wheels_result[3].theta = t_vars[6] * 180.0f / M_PI;
  258. LOG(INFO) << wheels_result[0].info();
  259. LOG(INFO) << wheels_result[1].info();
  260. LOG(INFO) << wheels_result[2].info();
  261. LOG(INFO) << wheels_result[3].info();
  262. return true;
  263. }
  264. std::vector<float> WheelCeresDetector::singleWheelModel() {
  265. float min = -2;
  266. float max = 0.5;
  267. float e = 0.001;
  268. std::vector<float> line;
  269. pcl::PointCloud<pcl::PointXYZ>::Ptr model(new pcl::PointCloud<pcl::PointXYZ>);
  270. for (int i = min / e; i < max / e; i++) {
  271. float x = i * e;
  272. float y = std::min<float>(exp(-x * x), 1.0f - 1.0f / (1.0f + exp(-400 * (x - 0.025))));
  273. // float y = std::max<float>(-100 * x * x + 1, 0);
  274. y = 1.0 / (1.0 + ceres::exp(-400 * (x + 0.025))) - 1.0 / (1.0 + ceres::exp(-400 * (x-0.025)));
  275. model->emplace_back(x, 1 - y, 0);
  276. line.emplace_back(y);
  277. }
  278. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/save/single_double_wheel_model.txt", model);
  279. return line;
  280. }
  281. std::vector<float> WheelCeresDetector::singleLeftWheelModel() {
  282. static std::vector<float> line;
  283. if (!line.empty()) {
  284. return line;
  285. }
  286. float min = -2;
  287. float max = 0.5;
  288. float e = 0.001;
  289. for (int i = min / e; i < max / e; i++) {
  290. float x = i * e;
  291. // float y = std::min<float>(exp(-x * x), 1.0f - 1.0f / (1.0f + exp(-400 * (x - 0.025))));
  292. // float y = std::max<float>(-100 * x * x + 1, 0);
  293. float y = 1.0 / (1.0 + ceres::exp(-400 * (x + 0.03))) - 1.0 / (1.0 + ceres::exp(-400 * (x-0.025)));
  294. line.emplace_back(y);
  295. }
  296. return line;
  297. }
  298. std::vector<float> WheelCeresDetector::singleRightWheelModel() {
  299. static std::vector<float> line;
  300. if (!line.empty()) {
  301. return line;
  302. }
  303. float min = -2;
  304. float max = 0.5;
  305. float e = 0.001;
  306. for (int i = min / e; i < max / e; i++) {
  307. float x = i * e;
  308. // float y = std::min<float>(exp(-x * x), 1.0f - 1.0f / (1.0f + exp(-400 * (x - 0.025))));
  309. // float y = std::max<float>(-100 * x * x + 1, 0);
  310. float y = 1.0 / (1.0 + ceres::exp(-400 * (x + 0.025))) - 1.0 / (1.0 + ceres::exp(-400 * (x-0.03)));
  311. line.emplace_back(y);
  312. }
  313. return line;
  314. }
  315. void WheelCeresDetector::doubleWheelModel( std::vector<float>& linel,std::vector<float>& liner) {
  316. float min = -2;
  317. float max = 0.5;
  318. float e = 0.001;
  319. pcl::PointCloud<pcl::PointXYZ>::Ptr model(new pcl::PointCloud<pcl::PointXYZ>);
  320. for (int i = min / e; i < max / e; i++) {
  321. float x = i * e;
  322. float y = std::min<float>(exp(-x * x), 1.0f - 1.0f / (1.0f + exp(-400 * (x - 0.025))));
  323. // float y = std::max<float>(-100 * x * x + 1, 0);
  324. model->emplace_back(x, 1 - y, 0);
  325. liner.emplace_back(y);
  326. }
  327. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/save/r_model.txt", model);
  328. min = -0.5;
  329. max = 2;
  330. e = 0.001;
  331. model->clear();
  332. for (int i = min / e; i < max / e; i++) {
  333. float x = i * e;
  334. float y = std::min<float>(exp(-x * x), 1.0f - 1.0f / (1.0f + exp(-400 * (-x - 0.025))));
  335. // float y = std::max<float>(-100 * x * x + 1, 0);
  336. model->emplace_back(x, 1 - y, 0);
  337. linel.emplace_back(y);
  338. }
  339. Point3D_tool::WriteTxtCloud(ETC_PATH PROJECT_NAME "/data/save/l_model.txt", model);
  340. }