laser_task_command.h 4.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114
  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. ~Laser_task();
  27. //初始化任务单,必须初始化之后才可以使用,(必选参数)
  28. // input:p_task_cloud_lock 三维点云的数据保护锁
  29. // output:p_task_point_cloud 三维点云容器的智能指针
  30. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  31. Error_manager task_init(std::mutex* p_task_cloud_lock,
  32. pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
  33. //初始化任务单,必须初始化之后才可以使用,(可选参数)
  34. // input:task_statu 任务状态
  35. // input:task_statu_information 状态说明
  36. // input:tast_receiver 接受对象
  37. // input:task_over_time 超时时间
  38. // input:task_frame_maxnum 点云的采集帧数最大值
  39. // input:task_save_flag 是否保存
  40. // input:task_save_path 保存路径
  41. // input:p_task_cloud_lock 三维点云的数据保护锁
  42. // output:p_task_pmutexoint_cloud 三维点云容器的智能指针
  43. //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
  44. Error_manager task_init(Task_statu task_statu,
  45. std::string task_statu_information,
  46. void* p_tast_receiver,
  47. std::chrono::milliseconds task_over_time,
  48. unsigned int task_frame_maxnum,
  49. bool task_save_flag,
  50. std::string task_save_path,
  51. std::mutex* p_task_cloud_lock,
  52. pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud
  53. );
  54. //push点云,把 point_xyz 添加到 p_task_point_cloud 里面。
  55. Error_manager task_push_point(pcl::PointXYZ* p_point_xyz);
  56. public:
  57. //获取 点云的采集帧数最大值
  58. unsigned int get_task_frame_maxnum();
  59. //获取采集的点云保存文件的使能标志位
  60. bool get_task_save_flag();
  61. //获取采集的点云保存路径
  62. std::string get_task_save_path();
  63. //获取 三维点云容器的智能指针
  64. std::mutex* get_task_cloud_lock();
  65. //获取 三维点云容器的智能指针
  66. pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
  67. //设置 点云的采集帧数最大值
  68. void set_task_frame_maxnum(unsigned int task_frame_maxnum);
  69. //设置采集的点云保存文件的使能标志位
  70. void set_task_save_flag(bool task_save_flag);
  71. //设置采集的点云保存路径
  72. void set_task_save_path(std::string task_save_path);
  73. //设置采集的点云保存标志位和路径
  74. void set_task_save_flag_and_path(bool task_save_flag, std::string task_save_path);
  75. protected:
  76. //点云的采集帧数最大值,任务输入
  77. unsigned int m_task_frame_maxnum;
  78. //雷达保存文件的使能标志位,//默认不保存,false
  79. bool m_task_save_flag;
  80. //点云保存文件的路径,任务输入
  81. std::string m_task_save_path;
  82. //三维点云的数据保护锁,任务输入, (实际上多个雷达会同时往一个pcl点云容器里面填充数据,防止数据冲突,需要对容器加锁.)
  83. std::mutex* mp_task_cloud_lock;
  84. //采集结果,三维点云容器的智能指针,任务输出
  85. //这里只是智能指针,实际内存由任务发送方管理管理,初始化时必须保证内存有效。
  86. pcl::PointCloud<pcl::PointXYZ>::Ptr mp_task_point_cloud;
  87. };
  88. #endif //__LASER_TASK_COMMAND__HH__