def.h 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163
  1. #ifndef __COMMON_DEF_H__
  2. #define __COMMON_DEF_H__
  3. #include <vector>
  4. #include <string>
  5. #include <map>
  6. #include <boost/thread/shared_mutex.hpp>
  7. typedef boost::unique_lock<boost::shared_mutex> U_Lock;
  8. typedef boost::shared_lock<boost::shared_mutex> S_Lock;
  9. struct Point {
  10. float x;
  11. float y;
  12. };
  13. struct Pose {
  14. float x;
  15. float y;
  16. float theta;
  17. };
  18. struct MapPoint {
  19. std::string name; //点名
  20. std::string id; //点ID
  21. std::string type; //点类型
  22. Pose pose; //点坐标
  23. };
  24. struct MapPath {
  25. std::string name; //路径名
  26. std::string id; //路径ID
  27. std::string type; //类型 直线,圆弧
  28. MapPoint start; //起始点ID
  29. MapPoint end; //终点ID
  30. float max_linear; //最大线速度
  31. float max_angular; //最大角速度
  32. bool enable; //能否使用
  33. bool forward; //是否能从起点到终点行驶
  34. bool reverse; //是否能从终点到起点行驶
  35. bool obstacle; //是否避障
  36. double drive_angle; //行驶角度
  37. };
  38. using Path = std::vector<Pose>;
  39. using Points = std::vector<Point>;
  40. using Area = std::vector<Point>;
  41. struct MapInfo {
  42. std::string name; //地图名
  43. std::string id; //地图ID
  44. int floor; //地图楼层
  45. Points origin_map; //原始地图数据
  46. Points shadow_map; //影子地图数据
  47. Points reflector_map; //反光板地图数据
  48. std::map<std::string, MapPath> paths; //地图路径 <id>
  49. std::map<std::string, MapPoint> points; //地图点 <id>
  50. };
  51. struct Map { //地图信息
  52. std::string name; //地图名
  53. std::string id; //地图ID
  54. };
  55. struct EmcyInfo { //急停信息
  56. bool hardware; //硬件急停
  57. bool software; //软件急停
  58. bool traffic; //交通管制急停
  59. };
  60. struct BatteryInfo { //电池信息
  61. bool charging; //是否充电
  62. double soc; //电量百分比
  63. double voltage; //电压
  64. double electric; //电流
  65. };
  66. struct LocationInfo { //定位信息
  67. std::string map_id; //当前地图ID
  68. double x; //x坐标
  69. double y; //y坐标
  70. double theta; //角度
  71. };
  72. struct ResourceInfo {
  73. std::string current_pose_id; //AGV当前所在点ID
  74. std::string current_pose_name; //AGV当前所在点名
  75. std::vector<MapPoint> path; //AGV任务路径
  76. };
  77. struct NavigationConfigInfo {
  78. Area origin_obstacle_area; //原始避障区域
  79. Area extend_obstacle_area; //扩展避障区域
  80. std::vector<Area> shield_area; //屏蔽区域
  81. float max_linear; //最大线速度
  82. float max_angular; //最大角速度
  83. float min_linear; //最小线速度
  84. float min_angular; //最小角速度
  85. float error_x; //到点x方向误差
  86. float error_y; //到点y方向误差
  87. float error_theta; //到点角度误差
  88. float dec; //减速度
  89. float acc; //加速度
  90. float slow_dist; //避障减距离
  91. float stop_dist; //避障停止距离
  92. float look_up_dist; //前瞻距离
  93. bool break_path; //是否分段导航
  94. bool face_angle; //是否转到朝向角度
  95. };
  96. struct LaserConfigInfo {
  97. std::string frame_id; //激光frame_id
  98. std::string topic; //激光数据topic
  99. float tf_x; //tf 坐标
  100. float tf_y;
  101. float tf_z;
  102. float tf_roll;
  103. float tf_pitch;
  104. float tf_yaw;
  105. };
  106. struct RobotInfo {
  107. std::string name; //AGV名
  108. std::string id; //AGV ID
  109. std::string type; //AGV类型 (二轮差速,单舵轮, 双舵轮, 四舵轮)
  110. std::string state; //AGV状态 (空闲,工作中,充电中)
  111. bool located; //AGV是否定位
  112. LocationInfo location; //定位信息
  113. std::map<std::string, MapInfo> maps; //地图信息 <地图id, 地图信息>
  114. EmcyInfo emcy; //急停信息
  115. BatteryInfo battery; //电池信息
  116. std::map<std::string, bool> gpio; //io信息 <io名,状态>
  117. ResourceInfo resource; //占用资源信息
  118. NavigationConfigInfo nav_config; //导航参数
  119. std::map<std::string, LaserConfigInfo> laser; //雷达参数
  120. };
  121. struct TaskInfo {
  122. std::string name; //任务名
  123. std::string id; //任务ID 唯一性
  124. std::string state; //任务状态 准备中 执行中 待执行 完成 终止
  125. unsigned int priority; //优先级 0~9 数值越大优先级越高,默认为0
  126. std::string start_time; //任务开始时间
  127. std::string finish_time; //任务完成时间
  128. std::string info; //任务信息
  129. };
  130. #endif