123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601 |
- #include "terminal_command_executor.h"
- #include <glog/logging.h>
- #include <chrono>
- #include <pcl/filters/passthrough.h>
- #include "../tool/pathcreator.h"
- ///增加获取wj电子围栏模块头文件
- #include "terminor_msg.pb.h"
- #include "MeasureRequest.h"
- std::mutex Terminor_Command_Executor::ms_mutex_scan_measure;
- //////以下两个函数用于测试,读取指定点云
- bool string2point(std::string str,pcl::PointXYZ& point)
- {
- std::istringstream iss;
- iss.str(str);
- float value;
- float data[3]={0};
- for(int i=0;i<3;++i)
- {
- if(iss>>value)
- {
- data[i]=value;
- }
- else
- {
- return false;
- }
- }
- point.x=data[0];
- point.y=data[1];
- point.z=data[2];
- return true;
- }
- pcl::PointCloud<pcl::PointXYZ>::Ptr ReadTxtCloud(std::string file)
- {
- std::ifstream fin(file.c_str());
- const int line_length=64;
- char str[line_length]={0};
- pcl::PointCloud<pcl::PointXYZ>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZ>);
- while(fin.getline(str,line_length))
- {
- pcl::PointXYZ point;
- if(string2point(str,point))
- {
- cloud->push_back(point);
- }
- }
- return cloud;
- }
- //////////
- Terminor_Command_Executor::Terminor_Command_Executor(Terminal::Terminor_parameter parameter)
- :m_terminor_statu(TERMINOR_READY), mp_command_thread(0),m_timeout_second(15),mb_force_quit(false)
- {
- m_terminor_parameter=parameter;
- mp_wj_lidar=NULL;
- }
- Error_manager Terminor_Command_Executor::force_stop_command()
- {
- mb_force_quit=true;
- //等待执行线程退出
- if(mp_command_thread!=NULL)
- {
- if(mp_command_thread->joinable())
- {
- mp_command_thread->join();
- delete mp_command_thread;
- mp_command_thread=NULL;
- }
- }
- return SUCCESS;
- }
- Terminor_Command_Executor::~Terminor_Command_Executor()
- {
- if(mp_command_thread!=0)
- {
- force_stop_command();
- if(mp_command_thread->joinable())
- {
- mp_command_thread->join();
- delete mp_command_thread;
- mp_command_thread=0;
- }
- }
- }
- TerminorStatu Terminor_Command_Executor::get_terminor_statu()
- {
- return m_terminor_statu;
- }
- Error_manager Terminor_Command_Executor::execute_command(std::vector<Laser_base*> lasers,Fence_controller* wj_lidar,
- Plc_Communicator* plc,Locater* locater,Verify_result* verify_tool,float timeout)
- {
- Error_manager code;
- //第一步检查输入参数合法性
- for(int i=0;i<lasers.size();++i)
- {
- if(lasers[i]==0)
- {
- char description[255]={0};
- sprintf(description,"terminor input laser* is null index:%d, terminor id:%d",i,m_terminor_parameter.id());
- return Error_manager(TERMINOR_INPUT_LASER_NULL,NORMAL,description);
- }
- }
- if(plc==0)
- {
- char description[255]={0};
- sprintf(description,"terminor input plc* is null terminor id:%d",m_terminor_parameter.id());
- return Error_manager(TERMINOR_INPUT_PLC_NULL,NORMAL,description);
- }
- if(wj_lidar==NULL)
- {
- char description[255]={0};
- sprintf(description,"terminor input wj_lidar* is null terminor id:%d",m_terminor_parameter.id());
- return Error_manager(TERMINOR_INPUT_LOCATER_NULL,NORMAL,description);
- }
- if(locater==0)
- {
- char description[255]={0};
- sprintf(description,"terminor input locater* is null terminor id:%d",m_terminor_parameter.id());
- return Error_manager(TERMINOR_INPUT_LOCATER_NULL,NORMAL,description);
- }
- mp_verify_tool=verify_tool;
- //第二步,雷达,plc以及定位模块是否能正常接收指令;
- for(int i=0;i<lasers.size();++i)
- {
- code=lasers[i]->check_laser();
- if(code!=SUCCESS)
- {
- LOG(ERROR)<<" terminor check laser error:"<<code.to_string()<<" terminor id :"<<m_terminor_parameter.id();
- return code;
- }
- }
- //检查plc状态
- code=plc->get_error();
- if(code!=SUCCESS)
- {
- LOG(ERROR)<<"terminor check plc error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
- return code;
- }
- //检查测量模块状态
- code=locater->get_error();
- if(code!=SUCCESS)
- {
- LOG(ERROR)<<"terminor check locater error : "<<code.to_string()<<" terminor id:"<<m_terminor_parameter.id();
- return code;
- }
- // 检查当前终端指令执行器的状态是否空闲;如果空闲,进入测量流程,设置忙碌状态
- std::lock_guard<std::mutex> t_lock(m_mutex_lock);
- if(get_terminor_statu()!=TERMINOR_READY)
- {
- char description[255]={0};
- sprintf(description,"terminor is not ready, terminor id:%d",m_terminor_parameter.id());
- return Error_manager(TERMINOR_NOT_READY,NORMAL,description);
- }
- //检查上次线程是否退出,并等待线程退出
- if(mp_command_thread!=0)
- {
- if(mp_command_thread->joinable())
- {
- mp_command_thread->join();
- delete mp_command_thread;
- mp_command_thread=0;
- }
- }
- //第二步接受指令,保存输入参数,更新指令状态为TERMINOR_BUSY,启动内部工作线程.返回SUCCESS
- mp_laser_vector=lasers;
- mp_plc=plc;
- mp_wj_lidar=wj_lidar;
- mp_locater=locater;
- m_terminor_statu=TERMINOR_BUSY;
- m_timeout_second=timeout;
- mp_command_thread=new std::thread(thread_command_working,this);
- if(mp_command_thread==0)
- {
- return Error_manager(TERMINOR_CREATE_WORKING_THREAD_FAILED,NORMAL,"terminor create thread failed");
- }
- return SUCCESS;
- }
- void Terminor_Command_Executor::thread_command_working(Terminor_Command_Executor* terminor)
- {
- if(terminor==NULL)
- {
- return ;
- }
- //执行指令,阻塞直到指令执行完成或者异常结束,此处如果失败,连续三次测量
- Error_manager code;
- int measure_times=0;
- while(terminor->mb_force_quit==false) {
- if (measure_times == 3)
- break;
- code = terminor->scanning_measuring();
- switch (code.get_error_code()) {
- case SUCCESS:
- break;
- case TERMINOR_LASER_TIMEOUT: {
- //雷达扫描超时,代表雷达故障,此时需要重置雷达模块
- }
- }
- if (code != SUCCESS ) {
- if(measure_times==2)
- {
- LOG(ERROR) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
- }
- else
- {
- LOG(WARNING) << " Measure times("<<measure_times<<") failed : "<< code.to_string();
- }
- measure_times++;
- }
- else {
- LOG(INFO) << " Measure complete!!! times:"<<measure_times;
- break;
- }
- }
- //根据结果执行上传任务
- code=terminor->post_measure_information();
- //更新终端状态为Ready状态
- terminor->m_terminor_statu=TERMINOR_READY;
- if (code != SUCCESS) {
- LOG(ERROR) << "Command measure execute failed : "<< code.to_string();
- }
- else {
- LOG(INFO) << "Command execute complete!!!";
- }
- }
- /*
- * 执行上传plc任务
- */
- Error_manager Terminor_Command_Executor::post_measure_information()
- {
- //计时起点
- auto t_start_point=std::chrono::system_clock::now();
- Error_manager code;
- //执行plc上传任务
- m_terminor_statu=TERMINOR_POSTING;
- Plc_Task* plc_task=new Plc_Task();
- measure_result measure_information;
- measure_information.x=m_measure_information.locate_x;
- measure_information.y=m_measure_information.locate_y;
- measure_information.angle=m_measure_information.locate_theta;
- measure_information.length=m_measure_information.locate_length;
- measure_information.width=m_measure_information.locate_width;
- measure_information.height=m_measure_information.locate_hight;
- measure_information.wheel_base=m_measure_information.locate_wheel_base;
- //plc终端编号从1开始,因此,上传给plc的终端编号必须+1
- measure_information.terminal_id=m_terminor_parameter.id()+1;
- measure_information.correctness=m_measure_information.locate_correct;
- plc_task->set_result(measure_information);
- code=mp_plc->execute_task(plc_task);
- while(code!=SUCCESS)
- {
- //判断是否强制退出
- if(mb_force_quit==true)
- {
- char description[255]={0};
- sprintf(description,"ternimal is force quit terminal id : %d",m_terminor_parameter.id());
- return Error_manager(TERMINOR_FORCE_QUIT,NORMAL,description);
- }
- //对于上传不成功,作失败处理,重新传输
- code=mp_plc->execute_task(plc_task);
- ///不成功,检测本次流程是否超时
- if(code!=SUCCESS)
- {
- auto t_end_point=std::chrono::system_clock::now();
- auto duration=std::chrono::duration_cast<std::chrono::milliseconds>(t_end_point - t_start_point);
- double second=double(duration.count()) *
- std::chrono::milliseconds::period::num / std::chrono::milliseconds::period::den;
- if(second>m_timeout_second)
- {
- //扫描超时处理
- return Error_manager(TERMINOR_POST_PLC_TIMEOUT,NORMAL,"post plc timeout");
- }
- usleep(1000*100);
- }
- }
- return code;
- }
- void Terminor_Command_Executor::set_save_root_path(std::string root)
- {
- m_save_root_path=root;
- }
- Error_manager Terminor_Command_Executor::scanning_measuring() {
- std::lock_guard<std::mutex> lock(ms_mutex_scan_measure);
- Error_manager code;
- Error_manager t_result;
- LOG(INFO) << ">>>>>>>>>>>> Enter terminator ID:" << m_terminor_parameter.id();
- //计时起点
- auto t_start_point = std::chrono::system_clock::now();
- //准备目录
- time_t tt;
- time(&tt);
- tt = tt + 8 * 3600; // transform the time zone
- tm *t = gmtime(&tt);
- char path[255] = {0};
- sprintf(path, "%s/%4d/%02d/%02d", m_save_root_path.c_str(),
- t->tm_year + 1900,
- t->tm_mon + 1,
- t->tm_mday);
- PathCreator path_creator;
- path_creator.CreateDatePath(path);
- std::string project_path = path_creator.GetCurPath();
- //第一步,启动雷达扫描点云,切换当前状态为扫描中
- //根据配置筛选雷达
- pcl::PointCloud<pcl::PointXYZ> scan_cloud;
- std::mutex cloud_lock;
- std::vector<Laser_task *> laser_task_vector;
- std::vector<Laser_base *> tp_lasers;
- for (int i = 0; i < m_terminor_parameter.laser_parameter_size(); ++i) {
- int laser_id = m_terminor_parameter.laser_parameter(i).id();
- int frame_count = m_terminor_parameter.laser_parameter(i).frame_count();
- if (frame_count <= 0) {
- LOG(WARNING) << "terminal parameter laser[" << laser_id << "] frame count is <0";
- continue;
- }
- if (laser_id >= 0 && laser_id < mp_laser_vector.size()) {
- //判断该id的雷达是否已经添加进去, 放置配置中出现重复的雷达编号
- bool tb_repeat = false;
- for (int j = 0; j < tp_lasers.size(); ++j) {
- if (tp_lasers[j] == mp_laser_vector[laser_id]) {
- tb_repeat = true;
- break;
- }
- }
- if (tb_repeat == false) {
- tp_lasers.push_back(mp_laser_vector[laser_id]);
- //创建扫描任务,
- Laser_task *laser_task = new Laser_task();
- //
- laser_task->task_init(TASK_CREATED, &scan_cloud, &cloud_lock);
- laser_task->set_task_frame_maxnum(frame_count);
- laser_task->set_save_path(project_path);
- laser_task_vector.push_back(laser_task);
- //发送任务单给雷达
- code = tp_lasers[i]->execute_task(laser_task);
- if (code != SUCCESS) {
- return code;
- }
- }
- }
- }
- if (tp_lasers.size() == 0) {
- return Error_manager(TERMINOR_NOT_CONTAINS_LASER, NORMAL, "terminal not contains laser");
- }
- m_terminor_statu = TERMINOR_SCANNING;
- //等待雷达完成任务单
- while (1)
- {
- //判断是否强制退出
- if (mb_force_quit == true) {
- char description[255] = {0};
- sprintf(description, "ternimal is force quit terminal id : %d", m_terminor_parameter.id());
- return Error_manager(TERMINOR_FORCE_QUIT, NORMAL, description);
- }
- int i = 0;
- for (; i < laser_task_vector.size(); ++i)
- {
- if (laser_task_vector[i]->is_task_end() == false)
- {
- if (laser_task_vector[i]->is_over_time())
- {
- //超时处理。取消任务。
- tp_lasers[i]->cancel_task();
- laser_task_vector[i]->set_task_statu(TASK_DEAD);
- code.error_manager_reset(Error_code::LASER_TASK_OVER_TIME, Error_level::MINOR_ERROR,
- " LASER_TASK is_over_time ");
- laser_task_vector[i]->set_task_error_manager(code);
- continue;
- //本次子任务超时死亡.直接进行下一个
- }
- else
- {
- //如果任务还在执行, 那就等待任务继续完成,等1ms
- //std::this_thread::sleep_for(std::chrono::milliseconds(1));
- std::this_thread::yield();
- break;
- //注意了:这里break之后, i != laser_task_vector.size()
- //这就表示仍然有子任务单没有结束.那就继续等待,,,直到所有任务完成或者超时.
- }
- }
- //else 任务完成就判断下一个
- }
- //如果下发的任务全部结束,那么汇总所有的结果, 并销毁下发的任务单。
- if(i == laser_task_vector.size() )
- {
- for ( int j = 0; j < laser_task_vector.size(); ++j)
- {
- if (laser_task_vector[i] != NULL) {
- //数据汇总,
- //由于 pcl::PointCloud<pcl::PointXYZ>::Ptr mp_task_point_cloud; 是所有任务单共用的,所以不用处理了。自动就在一起。
- //错误汇总
- t_result.compare_and_cover_error(laser_task_vector[j]->get_task_error_manager());
- //销毁下发的任务单。
- delete laser_task_vector[j];
- laser_task_vector[j] = NULL;
- }
- }
- laser_task_vector.clear();
- break;
- //退出while(1)
- }
- //else 直接通过, 然后重新进入 while (1)
- usleep(1000 * 100);
- }
- //暂时不做错误处理,
- // 如果有个别雷达扫描故障, 取消雷达子任务之后, 忽略错误
- //用其他正常的雷达扫描点云, 继续后面的流程,
- // 交给locate去定位识别, 如果识别不出来, 由locate来报错.
- if ( t_result != SUCCESS )
- {
- LOG(INFO) << " laser_task error :::: "<< t_result.to_string()<< this;
- // return t_result;
- }
- //检查雷达任务完成情况,是否是正常完成
- LOG(INFO) << " laser scanning over cloud size:" << scan_cloud.size();
- //第二步,根据区域筛选点云
- pcl::PointCloud<pcl::PointXYZ>::Ptr locate_cloud(new pcl::PointCloud<pcl::PointXYZ>);
- pcl::PassThrough<pcl::PointXYZ> passX;
- pcl::PassThrough<pcl::PointXYZ> passY;
- pcl::PassThrough<pcl::PointXYZ> passZ;
- passX.setInputCloud(scan_cloud.makeShared());
- passX.setFilterFieldName("x");
- passX.setFilterLimits(m_terminor_parameter.area_3d().min_x(), m_terminor_parameter.area_3d().max_x());
- passX.filter(*locate_cloud);
- passY.setInputCloud(locate_cloud);
- passY.setFilterFieldName("y");
- passY.setFilterLimits(m_terminor_parameter.area_3d().min_y(), m_terminor_parameter.area_3d().max_y());
- passY.filter(*locate_cloud);
- passY.setInputCloud(locate_cloud);
- passY.setFilterFieldName("z");
- passY.setFilterLimits(m_terminor_parameter.area_3d().min_z(), m_terminor_parameter.area_3d().max_z());
- passY.filter(*locate_cloud);
- LOG(INFO) << "筛选点云点数 : " << locate_cloud->size();
- //第三步,创建测量任务, 进入测量中
- Locate_task *locate_task = new Locate_task();
- locate_task->set_locate_cloud(locate_cloud);
- locate_task->set_save_path(project_path);
- m_terminor_statu = TERMINOR_MEASURING;
- code = mp_locater->execute_task(locate_task);
- m_measure_information.locate_correct = false;
- //获取测量结果
- Locate_information dj_locate_information = locate_task->get_locate_information();
- //释放locate task
- if (locate_task != NULL) {
- delete locate_task;
- locate_task = NULL;
- }
- if (code != SUCCESS) {
- return code;
- }
- //进入万集雷达流程--------
- Wj_lidar_Task *wj_task = new Wj_lidar_Task();
- code = wj_task->init();
- if (code != SUCCESS) {
- delete wj_task;
- return code;
- }
- wj_command t_wj_command;
- t_wj_command.terminal_id = m_terminor_parameter.id();
- t_wj_command.command_time = std::chrono::steady_clock::now();
- t_wj_command.timeout_in_milliseconds = 2000;
- wj_task->set_command(t_wj_command);
- code = mp_wj_lidar->execute_task(wj_task);
- if (code != SUCCESS) {
- delete wj_task;
- return code;
- }
- ///万集测量正确,对比两数据
- wj_measure_result wj_result;
- code = wj_task->get_result(wj_result);
- if (code != SUCCESS) {
- delete wj_task;
- return code;
- }
- Locate_information wj_locate_information;
- wj_locate_information.locate_x = wj_result.x;
- wj_locate_information.locate_y = wj_result.y;
- wj_locate_information.locate_theta = wj_result.angle;
- wj_locate_information.locate_wheel_base = wj_result.wheel_base;
- wj_locate_information.locate_width = wj_result.width;
- //对比两个数据
- float offset_x = fabs(dj_locate_information.locate_x - wj_locate_information.locate_x);
- float offset_y = fabs(dj_locate_information.locate_y - wj_locate_information.locate_y);
- float offset_angle = fabs(dj_locate_information.locate_theta - wj_locate_information.locate_theta);
- float offset_width = fabs(dj_locate_information.locate_width - wj_locate_information.locate_width);
- float offset_wheel_base = fabs(
- dj_locate_information.locate_wheel_base - wj_locate_information.locate_wheel_base);
- if (offset_x > 100 || offset_y > 150 || offset_angle > 5 || offset_wheel_base > 550 || offset_width > 250) {
- LOG(WARNING) << "chekc failed. (offset x>100, y>150, angle>5, wheel_base>550, width>250): " << offset_x
- << " " << offset_y << " " << offset_angle << " " << offset_wheel_base << " " << offset_width;
- return Error_manager(TERMINOR_CHECK_RESULTS_ERROR, NORMAL, "check results failed ");
- }
- ///根据sigmod函数计算角度权重
- double angle_weight=1.0-1.0/(1.0+exp(-offset_angle/1.8));
- ///根据两个结果选择最优结果,中心点选择万集雷达,角度选择两值加权,轴距已以2750为基准作卡尔曼滤波
- ///车长以大疆雷达为准,车宽以万集雷达为准,高以大疆雷达为准
- m_measure_information.locate_x = wj_locate_information.locate_x;
- m_measure_information.locate_y = wj_locate_information.locate_y;
- m_measure_information.locate_theta =angle_weight * wj_locate_information.locate_theta +
- (1.0-angle_weight) * dj_locate_information.locate_theta;
- float dj_distance = fabs(dj_locate_information.locate_wheel_base - 2750);
- float wj_distance = fabs(wj_locate_information.locate_wheel_base - 2750);
- float weight_dj = wj_distance / (dj_distance + wj_distance);
- float weight_wj = dj_distance / (dj_distance + wj_distance);
- m_measure_information.locate_wheel_base = weight_dj * dj_locate_information.locate_wheel_base +
- weight_wj * wj_locate_information.locate_wheel_base;
- m_measure_information.locate_length = dj_locate_information.locate_length;
- m_measure_information.locate_width = wj_locate_information.locate_width;
- m_measure_information.locate_hight = dj_locate_information.locate_hight;
- m_measure_information.locate_correct = true;
- ////如果测量正确,检验结果
- if (mp_verify_tool != NULL) {
- cv::RotatedRect rotated_rect;
- rotated_rect.center = cv::Point2f(m_measure_information.locate_x, m_measure_information.locate_y);
- rotated_rect.angle = m_measure_information.locate_theta;
- float ext_length = 720;
- float robot_width = 2650.0;
- float new_length = m_measure_information.locate_length + ext_length * 2.0;
- rotated_rect = create_rotate_rect(new_length, robot_width, m_measure_information.locate_theta,
- m_measure_information.locate_x, m_measure_information.locate_y);
- code = mp_verify_tool->verify(rotated_rect, m_measure_information.locate_hight, false);
- m_measure_information.locate_correct = (code == SUCCESS);
- delete wj_task;
- return code;
- } else {
- delete wj_task;
- }
- return code;
- }
- cv::RotatedRect Terminor_Command_Executor::create_rotate_rect(float length,float width,float angle,float cx,float cy)
- {
- const double C_PI=3.14159265;
- float theta=C_PI*(angle/180.0);
- float a00=cos(theta);
- float a01=-sin(theta);
- float a10=sin(theta);
- float a11=cos(theta);
- cv::Point2f point[4];
- point[0].x=-length/2.0;
- point[0].y=-width/2.0;
- point[1].x=-length/2.0;
- point[1].y=width/2.0;
- point[2].x=length/2.0;
- point[2].y=-width/2.0;
- point[3].x=length/2.0;
- point[3].y=width/2.0;
- std::vector<cv::Point2f> point_vec;
- for(int i=0;i<4;++i)
- {
- float x=point[i].x*a00+point[i].y*a01+cx;
- float y=point[i].x*a10+point[i].y*a11+cy;
- point_vec.push_back(cv::Point2f(x,y));
- }
- return cv::minAreaRect(point_vec);
- }
|