1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677 |
- //
- // Created by huli on 2020/9/8.
- //
- #ifndef NNXX_TESTS_WANJI_LIDAR_TASK_H
- #define NNXX_TESTS_WANJI_LIDAR_TASK_H
- #include "Point2D.h"
- #include "Point3D.h"
- #include <pcl/point_types.h>
- #include <pcl/common/common.h>
- #include "../error_code/error_code.h"
- #include <vector>
- #include <mutex>
- #include "../task/task_command_manager.h"
- //万集雷达模块的任务指令,从Task_Base继承,
- class Wanji_lidar_scan_task:public Task_Base
- {
- public:
- Wanji_lidar_scan_task();
- Wanji_lidar_scan_task(const Wanji_lidar_scan_task& other)= default;
- Wanji_lidar_scan_task& operator =(const Wanji_lidar_scan_task& other)= default;
- ~Wanji_lidar_scan_task();
- public://API functions
- //初始化任务单,必须初始化之后才可以使用,(必选参数)
- // input:p_task_cloud_lock 三维点云的数据保护锁
- // output:p_task_point_cloud 三维点云容器的智能指针
- //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
- Error_manager task_init(std::chrono::system_clock::time_point command_time,
- std::mutex* p_task_cloud_lock,
- pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud);
- //初始化任务单,必须初始化之后才可以使用,(可选参数)
- // input:task_statu 任务状态
- // input:task_statu_information 状态说明
- // input:tast_receiver 接受对象
- // input:task_over_time 超时时间
- // input:p_task_cloud_lock 三维点云的数据保护锁
- // output:p_task_pmutexoint_cloud 三维点云容器的智能指针
- //注:task_frame_maxnum默认为0,如果为0,则使用laser默认的点云的采集帧数最大值 TASK_FRAME_MAXNUM_DEFAULT
- Error_manager task_init(Task_statu task_statu,
- std::string task_statu_information,
- void* p_tast_receiver,
- std::chrono::milliseconds task_over_time,
- std::chrono::system_clock::time_point command_time,
- std::mutex* p_task_cloud_lock,
- pcl::PointCloud<pcl::PointXYZ>::Ptr p_task_point_cloud
- );
- public://get or set member variable
- std::chrono::system_clock::time_point get_command_time();
- //获取 三维点云容器的智能指针;
- std::mutex* get_task_cloud_lock();
- //获取 三维点云容器的智能指针
- pcl::PointCloud<pcl::PointXYZ>::Ptr get_task_point_cloud();
- protected://member variable
- //下发指令的时间点. 从command_time提前一个扫描周期, 然后取最新的点
- std::chrono::system_clock::time_point m_command_time;
- //三维点云的数据保护锁,任务输入, (实际上多个雷达会同时往一个pcl点云容器里面填充数据,防止数据冲突,需要对容器加锁.)
- std::mutex* mp_task_cloud_lock;
- //采集结果,三维点云容器的智能指针,任务输出
- //这里只是智能指针,实际内存由任务发送方管理管理,初始化时必须保证内存有效。
- pcl::PointCloud<pcl::PointXYZ>::Ptr mp_task_point_cloud;
- private:
- };
- #endif //NNXX_TESTS_WANJI_LIDAR_TASK_H
|