laser_manager_task.h 6.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162
  1. /*
  2. * Laser_manager_task 是雷达管理的任务单。
  3. * 外部通过它对 Laser_manager 下发任务。
  4. *
  5. //用法:上级直接调用 Laser_manager 的接口函数 execute_task ,并将 Laser_manager_task 类作为参数传递
  6. // Laser_manager 类则按照 Laser_manager_task 的功能码和指定的参数,执行相应的功能
  7. //并将结果填充到 Laser_manager_task ,返回给上级。
  8. *
  9. *
  10. * */
  11. #ifndef LASER_MANAGER_TASK_H
  12. #define LASER_MANAGER_TASK_H
  13. #include <pcl/point_types.h>
  14. #include <pcl/common/common.h>
  15. #include "../error_code/error_code.h"
  16. #include <vector>
  17. #include <mutex>
  18. #include "../task/task_command_manager.h"
  19. #include "../laser/laser_task_command.h"
  20. #include "../laser/Laser.h"
  21. class Laser_manager_task:public Task_Base
  22. {
  23. public://API functions
  24. //构造函数,构造函数锁定任务类型为 LASER_MANGER_SCAN_TASK ,后续不允许更改
  25. Laser_manager_task();
  26. Laser_manager_task(const Laser_manager_task& other) = delete;
  27. ~Laser_manager_task();
  28. //初始化任务单,必须初始化之后才可以使用,(必选参数)
  29. // input:p_task_cloud_lock 三维点云的数据保护锁
  30. // output:p_task_point_cloud 三维点云容器的智能指针
  31. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  32. Error_manager task_init(std::mutex* p_task_cloud_lock,
  33. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr>* p_task_point_cloud_map);
  34. //初始化任务单,必须初始化之后才可以使用,(可选参数)
  35. // input:task_statu 任务状态
  36. // input:task_statu_information 状态说明
  37. // input:tast_receiver 接受对象
  38. // input:task_over_time 超时时间
  39. // input:task_frame_maxnum 点云的采集帧数最大值
  40. // input:task_save_flag 是否保存
  41. // input:task_save_path 保存路径
  42. // input:p_task_cloud_lock 三维点云的数据保护锁
  43. // output:p_task_point_cloud 三维点云容器的智能指针
  44. // input:m_is_select_all_laser 是否选取所有的雷达
  45. // input:select_laser_number_vector 选取的指定雷达id
  46. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  47. Error_manager task_init(Task_statu task_statu,
  48. std::string task_statu_information,
  49. void* p_tast_receiver,
  50. std::chrono::milliseconds task_over_time,
  51. bool task_save_flag,
  52. std::string task_save_path,
  53. std::mutex* p_task_cloud_lock,
  54. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr>* p_task_point_cloud_map,
  55. bool cloud_aggregation_flag,
  56. unsigned int task_frame_maxnum,
  57. bool is_select_all_laser,
  58. std::vector<int> select_laser_id_vector
  59. );
  60. //把 Laser_manager_task 转化为 Laser_task,注意 task_statu 从外部载入。
  61. //output:p_laser_task 雷达扫描任务的指针,
  62. //input:laser_index 雷达编号
  63. //input:p_laser_base 接受任务的 子雷达
  64. //input:task_statu 外部载入的任务状态,默认为 TASK_CREATED
  65. //input:task_over_time 超时时间,一般要比上级任务的时间短一些
  66. Error_manager trans_to_laser_task(Laser_task * p_laser_task, int laser_index,Laser_base* p_laser_base,
  67. Task_statu task_statu = TASK_CREATED,
  68. std::chrono::milliseconds task_over_time = std::chrono::milliseconds(TASK_OVER_TIME_DEFAULT));
  69. public://get or set member variable
  70. //获取 点云的采集帧数最大值
  71. unsigned int get_task_frame_maxnum();
  72. //获取采集的点云保存文件的使能标志位
  73. bool get_task_save_flag();
  74. //获取采集的点云保存路径
  75. std::string get_task_save_path();
  76. //获取 三维点云容器的智能指针
  77. std::mutex* get_task_cloud_lock();
  78. //获取 三维点云容器的智能指针map
  79. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr>* get_task_point_cloud_map();
  80. //获取 所有雷达的三维点云是否聚集的标志位
  81. bool get_cloud_aggregation_flag();
  82. //设置 点云的采集帧数最大值
  83. void set_task_frame_maxnum(unsigned int task_frame_maxnum);
  84. //设置采集的点云保存文件的使能标志位
  85. void set_task_save_flag(bool task_save_flag);
  86. //设置采集的点云保存路径
  87. void set_task_save_path(std::string task_save_path);
  88. //设置采集的点云保存标志位和路径
  89. void set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path);
  90. //设置 三维点云容器的锁
  91. void set_task_cloud_lock(std::mutex* p_task_cloud_lock);
  92. //设置 三维点云容器的智能指针
  93. void set_task_point_cloud(std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr>* p_task_point_cloud_map);
  94. //设置 所有雷达的三维点云是否聚集的标志位
  95. void set_cloud_aggregation_flag(bool cloud_aggregation_flag);
  96. //获取 是否选取所有的雷达
  97. bool get_select_all_laser_flag();
  98. //设置 是否选取所有的雷达
  99. void set_select_all_laser_flag( bool select_all_laser_flag);
  100. //获取 被选中的雷达编号。
  101. std::vector<int>& get_select_laser_id_vector();
  102. //设置 被选中的雷达编号。
  103. void set_select_laser_id_vector(std::vector<int>& select_laser_id_vector);
  104. protected://member variable
  105. //点云的采集帧数最大值,任务输入
  106. unsigned int m_task_frame_maxnum;
  107. //雷达保存文件的使能标志位,//默认不保存,false
  108. bool m_task_save_flag;
  109. //点云保存文件的路径,任务输入
  110. std::string m_task_save_path;
  111. //三维点云的数据保护锁,任务输入
  112. std::mutex* mp_task_cloud_lock;
  113. //采集结果,三维点云容器的map指针,任务输出, map的内存由发送方管理,
  114. //map内部是空的, 处理任务过程再往里面push点云
  115. std::map<int,pcl::PointCloud<pcl::PointXYZ>::Ptr>* mp_task_point_cloud_map;
  116. //所有雷达的三维点云是否聚集的标志位,
  117. bool m_cloud_aggregation_flag;
  118. //m_cloud_aggregation_flag==true :: mp_task_point_cloud_map里面只有一个cloud
  119. //m_cloud_aggregation_flag==false:: mp_task_point_cloud_map里面有很多个cloud, 每个雷达的数据都是独立的.
  120. bool m_select_all_laser_flag; //是否选取所有的雷达。默认为true
  121. std::vector<int> m_select_laser_id_vector; //被选中的雷达编号。
  122. //注:当 m_is_select_all_laser 为true时,m_select_laser_number_vector不用写。
  123. //注:当 m_is_select_all_laser 为false时,m_select_laser_number_vector 必须填写,不能为空。否则报错。
  124. private:
  125. };
  126. #endif //LASER_MANAGER_TASK_H