laser_task_command.h 5.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133
  1. //laser_task_command,是雷达任务指令的相关功能
  2. //功能:用作应用层向laser模块传输任务,的指令消息
  3. //用法:应用层直接调用laser的接口函数,并将Laser_task类作为参数传递
  4. //CLaser类则按照Laser_task的功能码和指定的参数,执行相应的功能
  5. //并将结果填充到Laser_task,返回给应用层
  6. #ifndef __LASER_TASK_COMMAND__HH__
  7. #define __LASER_TASK_COMMAND__HH__
  8. #include "Point2D.h"
  9. #include "Point3D.h"
  10. #include <pcl/point_types.h>
  11. #include <pcl/common/common.h>
  12. #include "../error_code/error_code.h"
  13. #include <vector>
  14. #include <mutex>
  15. #include "../task/task_command_manager.h"
  16. //任务点云的采集帧数最大值,默认值1000
  17. #define TASK_FRAME_MAXNUM_DEFAULT 1000
  18. //雷达模块的任务指令,从Task_Base继承,
  19. //补充了雷达专属的数据输入和输出
  20. class Laser_task:public Task_Base
  21. {
  22. public:
  23. //构造函数,构造函数锁定任务类型为LASER_TASK,后续不允许更改
  24. Laser_task();
  25. //析构函数
  26. virtual ~Laser_task();
  27. //初始化任务单,必须初始化之后才可以使用,(必选参数)
  28. // input:task_statu 任务状态
  29. // output:p_task_point_cloud 三维点云容器的智能指针
  30. // input:p_task_cloud_lock 三维点云的数据保护锁
  31. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  32. Error_manager task_init(Task_statu task_statu,
  33. pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
  34. std::mutex* p_task_cloud_lock);
  35. //初始化任务单,必须初始化之后才可以使用,(可选参数)
  36. // input:task_statu任务状态
  37. // input:task_statu_information状态说明
  38. // input:task_frame_maxnum点云的采集帧数最大值
  39. // output:p_task_point_cloud 三维点云容器的智能指针
  40. // input:p_task_cloud_lock 三维点云的数据保护锁
  41. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  42. Error_manager task_init(Task_statu task_statu,
  43. std::string & task_statu_information,
  44. unsigned int task_frame_maxnum,
  45. pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud,
  46. std::mutex* p_task_cloud_lock);
  47. //初始化任务单,必须初始化之后才可以使用,(可选参数)
  48. // input:task_statu 任务状态
  49. // input:task_statu_information 状态说明
  50. // input:tast_receiver 接受对象
  51. // input:task_over_time 超时时间
  52. // input:task_frame_maxnum 点云的采集帧数最大值
  53. // input:task_save_flag 是否保存
  54. // input:task_save_path 保存路径
  55. // input:p_task_cloud_lock 三维点云的数据保护锁
  56. // output:p_task_pmutexoint_cloud 三维点云容器的智能指针
  57. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  58. Error_manager task_init(Task_statu task_statu,
  59. std::string task_statu_information,
  60. void* p_tast_receiver,
  61. std::chrono::milliseconds task_over_time,
  62. unsigned int task_frame_maxnum,
  63. bool task_save_flag,
  64. std::string task_save_path,
  65. std::mutex* p_task_cloud_lock,
  66. pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud
  67. );
  68. //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
  69. Error_manager task_push_point(pcl::PointXYZ point_xyz);
  70. public:
  71. //获取 点云的采集帧数最大值
  72. unsigned int get_task_frame_maxnum();
  73. //获取采集的点云保存路径
  74. std::string get_task_save_path();
  75. //获取 三维点云容器的智能指针
  76. pcl::PointCloud<pcl::PointXYZ>* get_task_point_cloud();
  77. //设置 任务状态
  78. void set_task_statu(Task_statu task_statu);
  79. //设置 任务状态说明
  80. void set_task_statu_information(std::string & task_statu_information);
  81. //设置 点云的采集帧数最大值
  82. void set_task_frame_maxnum(unsigned int task_frame_maxnum);
  83. //设置采集的点云保存路径
  84. void set_task_save_path(std::string task_save_path);
  85. //设置 三维点云容器的智能指针
  86. void set_task_point_cloud(pcl::PointCloud<pcl::PointXYZ>* p_task_point_cloud);
  87. //设置 错误码
  88. void set_task_error_manager(Error_manager & error_manager);
  89. //获取采集的点云保存路径
  90. std::string get_save_path();
  91. //设置采集的点云保存路径
  92. void set_save_path(std::string save_path);
  93. protected:
  94. //点云的采集帧数最大值,任务输入
  95. unsigned int m_task_frame_maxnum;
  96. std::string m_save_path;
  97. //点云保存文件的路径,任务输入
  98. std::string m_task_save_path;
  99. //三维点云的数据保护锁,任务输入
  100. std::mutex* mp_task_cloud_lock;
  101. //采集结果,三维点云容器的智能指针,任务输出
  102. //这里只是指针,实际内存由应用层管理,初始化时必须保证内存有效。
  103. pcl::PointCloud<pcl::PointXYZ>* mp_task_point_cloud;
  104. };
  105. #endif //__LASER_TASK_COMMAND__HH__