detect_wheel_ceres.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352
  1. //
  2. // Created by zx on 2020/7/1.
  3. //
  4. #include "detect_wheel_ceres.h"
  5. #include <ceres/cubic_interpolation.h>
  6. #include <pcl/common/transforms.h>
  7. constexpr float kMinProbability = 0.0f;
  8. constexpr float kMaxProbability = 1.f - kMinProbability;
  9. constexpr float kMaxCorrespondenceCost = 1.f - kMinProbability;
  10. constexpr int kPadding = INT_MAX / 4;
  11. class GridArrayAdapter {
  12. public:
  13. enum { DATA_DIMENSION = 1 };
  14. explicit GridArrayAdapter(const cv::Mat& grid) : grid_(grid) {}
  15. void GetValue(const int row, const int column, double* const value) const {
  16. if (row < kPadding || column < kPadding || row >= NumRows() - kPadding ||
  17. column >= NumCols() - kPadding) {
  18. *value = kMaxCorrespondenceCost;
  19. } else {
  20. *value = static_cast<double>(grid_.at<double >(row - kPadding, column - kPadding));
  21. }
  22. }
  23. int NumRows() const {
  24. return grid_.rows + 2 * kPadding;
  25. }
  26. int NumCols() const {
  27. return grid_.cols + 2 * kPadding;
  28. }
  29. private:
  30. const cv::Mat& grid_;
  31. };
  32. class CostFunctor {
  33. private:
  34. cv::Mat m_map;
  35. double m_scale;
  36. pcl::PointCloud<pcl::PointXYZ> m_left_front_cloud; //左前点云
  37. pcl::PointCloud<pcl::PointXYZ> m_right_front_cloud; //右前点云
  38. pcl::PointCloud<pcl::PointXYZ> m_left_rear_cloud; //左后点云
  39. pcl::PointCloud<pcl::PointXYZ> m_right_rear_cloud; //右后点云
  40. public:
  41. CostFunctor(pcl::PointCloud<pcl::PointXYZ> left_front,pcl::PointCloud<pcl::PointXYZ> right_front,
  42. pcl::PointCloud<pcl::PointXYZ> left_rear,pcl::PointCloud<pcl::PointXYZ> right_rear,
  43. cv::Mat& map,double scale)
  44. {
  45. m_map=map;
  46. m_scale=scale;
  47. m_left_front_cloud=left_front;
  48. m_right_front_cloud=right_front;
  49. m_left_rear_cloud=left_rear;
  50. m_right_rear_cloud=right_rear;
  51. }
  52. template <typename T>
  53. bool operator()(const T* const variable, T* residual) const {
  54. T cx = variable[0];
  55. T cy = variable[1];
  56. T theta = variable[2];
  57. T length = variable[3];
  58. T width = variable[4];
  59. T theta_front = variable[5];
  60. //整车旋转
  61. Eigen::Rotation2D<T> rotation(theta);
  62. Eigen::Matrix<T, 2, 2> rotation_matrix = rotation.toRotationMatrix();
  63. //左前偏移
  64. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_front(length / 2.0, width / 2.0);
  65. //右前偏移
  66. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_front(length / 2.0, -width / 2.0);
  67. //左后偏移
  68. Eigen::Matrix<T, 2, 1> wheel_center_normal_left_rear(-length / 2.0, width / 2.0);
  69. //右后偏移
  70. Eigen::Matrix<T, 2, 1> wheel_center_normal_right_rear(-length / 2.0, -width / 2.0);
  71. //前轮旋转
  72. Eigen::Rotation2D<T> rotation_front(theta_front);
  73. Eigen::Matrix<T, 2, 2> rotation_matrix_front = rotation_front.toRotationMatrix();
  74. const GridArrayAdapter adapter(m_map);
  75. ceres::BiCubicInterpolator<GridArrayAdapter> interpolator(adapter);
  76. double rows = m_map.rows;
  77. double cols = m_map.cols;
  78. //左前轮
  79. int left_front_num = m_left_front_cloud.size();
  80. for (int i = 0; i < m_left_front_cloud.size(); ++i) {
  81. const Eigen::Matrix<T, 2, 1> point((T(m_left_front_cloud[i].x) - cx),
  82. (T(m_left_front_cloud[i].y) - cy));
  83. //减去经过车辆旋转计算的左前中心
  84. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_front;
  85. //旋转
  86. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  87. interpolator.Evaluate(point_rotation(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  88. point_rotation(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  89. &residual[i]);
  90. }
  91. //右前轮
  92. int right_front_num = m_right_front_cloud.size();
  93. for (int i = 0; i < m_right_front_cloud.size(); ++i) {
  94. const Eigen::Matrix<T, 2, 1> point((T(m_right_front_cloud[i].x) - cx),
  95. (T(m_right_front_cloud[i].y) - cy));
  96. //减去经过车辆旋转计算的左前中心
  97. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_front;
  98. //旋转
  99. const Eigen::Matrix<T, 2, 1> point_rotation = rotation_matrix_front * tanslate_point;
  100. interpolator.Evaluate(point_rotation(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  101. point_rotation(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  102. &residual[left_front_num + i]);
  103. }
  104. //左后轮
  105. int left_rear_num = m_left_rear_cloud.size();
  106. for (int i = 0; i < m_left_rear_cloud.size(); ++i) {
  107. const Eigen::Matrix<T, 2, 1> point((T(m_left_rear_cloud[i].x) - cx),
  108. (T(m_left_rear_cloud[i].y) - cy));
  109. //减去经过车辆旋转计算的左前中心
  110. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_left_rear;
  111. interpolator.Evaluate(tanslate_point(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  112. tanslate_point(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  113. &residual[left_front_num + right_front_num + i]);
  114. }
  115. //右后轮
  116. for (int i = 0; i < m_right_rear_cloud.size(); ++i) {
  117. const Eigen::Matrix<T, 2, 1> point((T(m_right_rear_cloud[i].x) - cx),
  118. (T(m_right_rear_cloud[i].y) - cy));
  119. //减去经过车辆旋转计算的左前中心
  120. const Eigen::Matrix<T, 2, 1> tanslate_point = rotation_matrix * point - wheel_center_normal_right_rear;
  121. interpolator.Evaluate(tanslate_point(1, 0) * m_scale + rows / 2.0 + 0.5 + T(kPadding),
  122. tanslate_point(0, 0) * m_scale + cols / 2.0 + 0.5 + T(kPadding),
  123. &residual[left_front_num + right_front_num + left_rear_num + i]);
  124. }
  125. return true;
  126. }
  127. private:
  128. };
  129. detect_wheel_ceres::detect_wheel_ceres()
  130. {
  131. /////创建地图
  132. int cols=800;
  133. int rows=200;
  134. int L=std::min(rows,cols);
  135. cv::Mat map=cv::Mat::ones(L,L,CV_64F);
  136. //map=map*255;
  137. cv::Point center(L/2,L/2);
  138. float K=L*0.08;
  139. for(int n=0;n<L;n+=2)
  140. {
  141. cv::Size size(n+2,n+2);
  142. cv::Rect rect(center-cv::Point(n/2,n/2),size);
  143. if(n<K*2)
  144. cv::rectangle(map,rect,3.0*float(K*2-n)/float(L));
  145. else
  146. cv::rectangle(map,rect,float(n-K*2)/float(L));
  147. }
  148. cv::resize(map,map,cv::Size(cols,rows));
  149. cv::GaussianBlur(map,m_map,cv::Size(7,7),3,3);
  150. }
  151. detect_wheel_ceres::~detect_wheel_ceres(){}
  152. bool detect_wheel_ceres::detect(std::vector<pcl::PointCloud<pcl::PointXYZ>> cloud_vec,
  153. double& cx,double& cy,double& theta,double& wheel_base,double& width,double& front_theta)
  154. {
  155. //清理点云
  156. m_left_front_cloud.clear();
  157. m_right_front_cloud.clear();
  158. m_left_rear_cloud.clear();
  159. m_right_rear_cloud.clear();
  160. //重新计算点云,按方位分割
  161. //第一步,计算整体中心,主轴方向
  162. pcl::PointCloud<pcl::PointXYZ> cloud_all;
  163. for(int i=0;i<cloud_vec.size();++i)
  164. {
  165. cloud_all+=cloud_vec[i];
  166. }
  167. if(cloud_all.size()<20)
  168. return false;
  169. Eigen::Vector4f centroid;
  170. pcl::compute3DCentroid(cloud_all, centroid);
  171. double center_x=centroid[0];
  172. double center_y=centroid[1];
  173. //计算外接旋转矩形
  174. std::vector<cv::Point2f> points_cv;
  175. for(int i=0;i<cloud_all.size();++i)
  176. {
  177. points_cv.push_back(cv::Point2f(cloud_all[i].x,cloud_all[i].y));
  178. }
  179. cv::RotatedRect rotate_rect=cv::minAreaRect(points_cv);
  180. //计算旋转矩形与X轴的夹角
  181. cv::Point2f vec;
  182. cv::Point2f vertice[4];
  183. rotate_rect.points(vertice);
  184. float len1 = pow(vertice[0].x - vertice[1].x, 2.0) + pow(vertice[0].y - vertice[1].y, 2.0);
  185. float len2 = pow(vertice[1].x - vertice[2].x, 2.0) + pow(vertice[1].y - vertice[2].y, 2.0);
  186. // 寻找长边,倾角为长边与x轴夹角
  187. if (len1 > len2)
  188. {
  189. vec.x = vertice[0].x - vertice[1].x;
  190. vec.y = vertice[0].y - vertice[1].y;
  191. }
  192. else
  193. {
  194. vec.x = vertice[1].x - vertice[2].x;
  195. vec.y = vertice[1].y - vertice[2].y;
  196. }
  197. float angle_x = 180.0 / M_PI * acos(vec.x / sqrt(vec.x * vec.x + vec.y * vec.y));
  198. //printf("rect theta: %.3f\n",angle_x);
  199. //第二步, 将没分点云旋转回去,计算点云重心所在象限
  200. for(int i=0;i<cloud_vec.size();++i)
  201. {
  202. pcl::PointCloud<pcl::PointXYZ> cloud=cloud_vec[i];
  203. Eigen::Affine3f traslation = Eigen::Affine3f::Identity();//初始化变换矩阵为单位矩阵
  204. // 平移
  205. traslation.translation() << -center_x, -center_y, 0.0;
  206. pcl::PointCloud<pcl::PointXYZ> translate_cloud;
  207. pcl::transformPointCloud(cloud, translate_cloud, traslation);
  208. // 旋转; Z 轴上旋转angle_x 弧度,Y轴上旋转0弧度
  209. Eigen::Affine3f rotation = Eigen::Affine3f::Identity();
  210. rotation.rotate(Eigen::AngleAxisf(-angle_x*M_PI/180.0, Eigen::Vector3f::UnitZ()));
  211. pcl::PointCloud<pcl::PointXYZ> transformed_cloud;
  212. pcl::transformPointCloud(translate_cloud, transformed_cloud, rotation);
  213. //计算重心
  214. Eigen::Vector4f centroid;
  215. pcl::compute3DCentroid(transformed_cloud, centroid);
  216. double x=centroid[0];
  217. double y=centroid[1];
  218. //计算象限
  219. if(x>0&&y>0)
  220. {
  221. //第一象限
  222. m_left_front_cloud=cloud;
  223. }
  224. if(x>0 && y<0)
  225. {
  226. //第四象限
  227. m_right_front_cloud=cloud;
  228. }
  229. if(x<0 && y>0)
  230. {
  231. //第二象限
  232. m_left_rear_cloud=cloud;
  233. }
  234. if(x<0 && y<0)
  235. {
  236. //第三象限
  237. m_right_rear_cloud=cloud;
  238. }
  239. }
  240. cx=center_x;
  241. cy=center_y;
  242. theta=-angle_x*M_PI/180.0;
  243. return Solve(cx,cy,theta,wheel_base,width,front_theta);
  244. }
  245. bool detect_wheel_ceres::Solve(double& x,double& y,double& theta,double& wheel_base,double& width,double& front_theta)
  246. {
  247. double SCALE=300.0;
  248. double cx=x;
  249. double cy=y;
  250. double init_theta=theta;
  251. double init_wheel_base=2.7;
  252. double init_width=1.55;
  253. double init_theta_front=0*M_PI/180.0;
  254. double variable[] = {cx,cy,init_theta,init_wheel_base,init_width,init_theta_front};
  255. // 第二部分:构建寻优问题
  256. ceres::Problem problem;
  257. //使用自动求导,将之前的代价函数结构体传入,第一个1是输出维度,即残差的维度,第二个1是输入维度,即待寻优参数x的维度。
  258. ceres::CostFunction* cost_function =new
  259. ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 6>(
  260. new CostFunctor(m_left_front_cloud,m_right_front_cloud,m_left_rear_cloud,m_right_rear_cloud,m_map,SCALE),
  261. m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  262. problem.AddResidualBlock(cost_function, NULL, variable); //向问题中添加误差项,本问题比较简单,添加一个就行。
  263. //第三部分: 配置并运行求解器
  264. ceres::Solver::Options options;
  265. options.use_nonmonotonic_steps=false;
  266. options.linear_solver_type = ceres::DENSE_QR; //配置增量方程的解法
  267. options.max_num_iterations=20;
  268. options.num_threads=1;
  269. options.minimizer_progress_to_stdout = false;//输出到cout
  270. ceres::Solver::Summary summary;//优化信息
  271. ceres::Solve(options, &problem, &summary);//求解!!!
  272. //std::cout << summary.BriefReport() << "\n";//输出优化的简要信息
  273. /*printf("x:%.3f,y:%.3f,theta:%.3f\nlength:%.3f,width:%.3f\ntheta_front:%.3f\n",
  274. x[0],x[1],x[2]*180.0/M_PI,x[3],x[4],x[5]*180.0/M_PI);*/
  275. double loss=summary.final_cost/(m_left_front_cloud.size()+m_right_front_cloud.size()+m_left_rear_cloud.size()+m_right_rear_cloud.size());
  276. x=variable[0];
  277. y=variable[1];
  278. theta=(-variable[2])*180.0/M_PI;
  279. wheel_base=variable[3];
  280. width=variable[4];
  281. front_theta=-(variable[5]*180.0/M_PI);
  282. if(theta>180.0)
  283. theta=theta-180.0;
  284. if(theta<0)
  285. theta+=180.0;
  286. //检验
  287. if(loss>0.03)
  288. return false;
  289. if (width < 1.350 || width > 2.000 || wheel_base > 3.000 || wheel_base < 2.200)
  290. {
  291. return false;
  292. }
  293. width+=0.15;//车宽+10cm
  294. //printf(" x:%.3f y: %.3f wheel:%.3f width:%.3f theta : %.3f front theta: %.3f\n",x,y,wheel_base,width,theta,front_theta);
  295. return true;
  296. }