obstacle.h 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202
  1. #ifndef _SPACE_OBSTACLE_AREA_H_
  2. #define _SPACE_OBSTACLE_AREA_H_
  3. #include <vector>
  4. #include <string>
  5. #include <iostream>
  6. #include <fstream>
  7. #include <stdio.h>
  8. #include <ros/ros.h>
  9. #include <ros/package.h>
  10. #include <sensor_msgs/LaserScan.h>
  11. #include <sensor_msgs/PointCloud2.h>
  12. #include <std_msgs/Int32.h>
  13. #include <geometry_msgs/PolygonStamped.h>
  14. #include <sensor_msgs/PointCloud.h>
  15. #include <boost/thread.hpp>
  16. #include <boost/thread/mutex.hpp>
  17. #include <Eigen/Cholesky>
  18. #include <Eigen/Core>
  19. #include <Eigen/Geometry>
  20. #include <space_lib/space_lib.h>
  21. #include "obstacle/rigid_transform.h"
  22. #include "common/common.h"
  23. #include <glog/logging.h>
  24. namespace obs
  25. {
  26. namespace obs_private_common
  27. {
  28. typedef struct {
  29. float x;
  30. float y;
  31. }Point;
  32. typedef struct {
  33. float x;
  34. float y;
  35. float theta;
  36. }Pose2D;
  37. typedef struct {
  38. float x;
  39. float y;
  40. float z;
  41. }Pose3D;
  42. typedef struct {
  43. std::vector<Pose2D> poses;
  44. }Area;
  45. typedef struct {
  46. std::vector<Pose2D> poses;
  47. }Path;
  48. struct Twist{
  49. Twist() : translation(0), rotate(0), horizontal(0)
  50. {}
  51. float translation;
  52. float horizontal;
  53. float rotate;
  54. };
  55. struct Obstacle {
  56. std::vector<Pose2D> obstacle_pose;
  57. ros::Time stamp;
  58. };
  59. } // namespace obs_private_common
  60. using namespace obs_private_common;
  61. class ObstacleIdentify
  62. {
  63. public:
  64. ObstacleIdentify();
  65. ~ObstacleIdentify();
  66. void updateFootPrint();
  67. bool isObstacleInArea(const float& x,
  68. const float& y,
  69. const float& theta,
  70. float& distance);
  71. bool isClose(common::Point pp);
  72. void stop()
  73. {
  74. for (auto& s : subs_) {
  75. s.shutdown();
  76. }
  77. on_ = false;
  78. }
  79. void start();
  80. private:
  81. struct IgnoreParam {
  82. IgnoreParam()
  83. {
  84. x_upper = 0.0;
  85. x_lower = 0.0;
  86. y_upper = 0.0;
  87. y_lower = 0.0;
  88. angle_upper = 0.0;
  89. angle_lower = 0.0;
  90. }
  91. float x_upper;
  92. float x_lower;
  93. float y_upper;
  94. float y_lower;
  95. float angle_upper;
  96. float angle_lower;
  97. };
  98. struct LaserParam {
  99. LaserParam() : min_range(0.0), max_range(1e10)
  100. {}
  101. float min_range;
  102. float max_range;
  103. float angle_increment;
  104. std::vector<IgnoreParam> ignores;
  105. };
  106. struct CameraParam {
  107. CameraParam() : filter_step(3),
  108. z_ceil(1e10),
  109. z_floor(-1e10),
  110. x_head(1e10),
  111. x_tail(-1e10),
  112. y_left(1e10),
  113. y_right(-1e10),
  114. pit_top(-1e10),
  115. pit_bot(-1e10)
  116. {}
  117. int filter_step;
  118. float z_ceil;
  119. float z_floor;
  120. float x_head;
  121. float x_tail;
  122. float y_left;
  123. float y_right;
  124. float pit_top;
  125. float pit_bot;
  126. std::vector<IgnoreParam> ignores;
  127. };
  128. struct CloseClose {
  129. CloseClose() :
  130. x(0.0),
  131. y(0.0),
  132. close_dist(0.0)
  133. {}
  134. float x;
  135. float y;
  136. float close_dist;
  137. };
  138. ros::NodeHandle nh_;
  139. void __laserCallback(const sensor_msgs::LaserScanConstPtr& msg);
  140. void __cameraCallback(const sensor_msgs::PointCloud2ConstPtr& msg);
  141. void __addObs(std::vector<Pose2D>& obs, const std::string sensor_name, ros::Time time);
  142. void __registerLaser();
  143. void __registerCamera();
  144. void __readConfig();
  145. void __getPrintFoot();
  146. std::vector<Pose2D> __getParseObs();
  147. bool __isIgnore(float x, float y, float angle, std::vector<IgnoreParam> ignores);
  148. bool __poseInArea(Pose2D point,Area area);
  149. Pose2D __trasformBaseLink(Pose2D pose, const Eigen::Matrix<float, 3, 3>& transform);
  150. Pose2D __localTransGlobal(Pose2D a, Pose2D b);
  151. std::vector<ros::Subscriber> subs_;
  152. ros::Publisher point_cloud_pub_, point_cloud3D_pub_;
  153. ros::Publisher dynamic_polygon_pub_;
  154. ros::Publisher static_polygon_pub_;
  155. std::vector<Pose2D> laser_date_;
  156. std::vector<CloseClose> close_closes_;
  157. std::map<std::string, Obstacle> obs_;
  158. std::map<std::string, CameraParam> camera_params_;
  159. std::map<std::string, LaserParam> laser_params_;
  160. Area foot_;
  161. std::map<std::string, Eigen::Matrix<float, 4, 4>> transforms_;
  162. bool debug_, debug_3d_, turn_off_, on_;
  163. float min_range_, max_range_;
  164. boost::mutex mutex_;
  165. };
  166. }
  167. #endif