#include "vehicle_upload.h" #include #include #include #include #include #include #include "modulecomm.h" #include "rawpic.pb.h" #include "chassis.pb.h" #include "platform_feedback.pb.h" #include "gpsimu.pb.h" extern std::string gstrserverip; extern std::string gstruploadPort; extern std::string gstruploadInterval; extern std::string gstrid; extern std::string gstrplateNumber; extern std::string gvehicleType; extern double gspeedWantAvg; // m/s extern double gwaitTime; // s extern char stryamlpath[256]; extern uint8_t gShift_Status;//3 p 4 r 5 n 6 d extern uint8_t gCtrlMode_Status; //0 auto 1 remote 2 stop 3 platform using org::jeecg::defsDetails::grpc::Empty; ///< other message using org::jeecg::defsDetails::grpc::GPSPoint; using org::jeecg::defsDetails::grpc::MapPoint; using org::jeecg::defsDetails::grpc::ShiftStatus; ///< other enum using org::jeecg::defsDetails::grpc::CtrlMode; DataExchangeClient::DataExchangeClient(std::shared_ptr channel) { stub_ = DataExchange::NewStub(channel); dec_yaml(stryamlpath); QObject::connect(this,&DataExchangeClient::destination_Recieved,this,&DataExchangeClient::destination_Recieved_Slot); QObject::connect(this,&DataExchangeClient::path_Updated,this,&DataExchangeClient::path_Updated_Slot); shmXodrRequest.mpa = iv::modulecomm::RegisterSend(shmXodrRequest.mstrmsgname,shmXodrRequest.mnBufferSize,shmXodrRequest.mnBufferCount); ModuleFun funupdate = std::bind(&DataExchangeClient::ListenFrontPicMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmPicFront.mpa = iv::modulecomm::RegisterRecvPlus(shmPicFront.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenRearPicMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmPicRear.mpa = iv::modulecomm::RegisterRecvPlus(shmPicRear.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenLeftPicMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmPicLeft.mpa = iv::modulecomm::RegisterRecvPlus(shmPicLeft.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenRightPicMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmPicRight.mpa = iv::modulecomm::RegisterRecvPlus(shmPicRight.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenChassisMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmChassis.mpa = iv::modulecomm::RegisterRecvPlus(shmChassis.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenGPSIMUMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmGPSIMU.mpa = iv::modulecomm::RegisterRecvPlus(shmGPSIMU.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenPlatformFeedbackMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmPlatformFeedback.mpa = iv::modulecomm::RegisterRecvPlus(shmPlatformFeedback.mstrmsgname,funupdate); funupdate = std::bind(&DataExchangeClient::ListenTraceMapMsg,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5); shmTraceMap.mpa = iv::modulecomm::RegisterRecvPlus(shmTraceMap.mstrmsgname,funupdate); } DataExchangeClient::~DataExchangeClient(void) { if(shmPicFront.mpa != nullptr)iv::modulecomm::Unregister(shmPicFront.mpa); if(shmPicRear.mpa != nullptr)iv::modulecomm::Unregister(shmPicRear.mpa); if(shmPicLeft.mpa != nullptr)iv::modulecomm::Unregister(shmPicLeft.mpa); if(shmPicRight.mpa != nullptr)iv::modulecomm::Unregister(shmPicRight.mpa); if(shmChassis.mpa != nullptr)iv::modulecomm::Unregister(shmChassis.mpa); if(shmGPSIMU.mpa != nullptr)iv::modulecomm::Unregister(shmGPSIMU.mpa); if(shmPlatformFeedback.mpa != nullptr)iv::modulecomm::Unregister(shmPlatformFeedback.mpa); requestInterruption(); while(this->isFinished() == false); } void DataExchangeClient::dec_yaml(const char *stryamlpath) { YAML::Node config; try { config = YAML::LoadFile(stryamlpath); } catch(YAML::BadFile &e) { std::cout<(); strncpy(shmPicFront.mstrmsgname,strmsgname.data(),255); shmPicFront.mnBufferSize = config["pic_front"]["buffersize"].as(); shmPicFront.mnBufferCount = config["pic_front"]["buffercount"].as(); std::cout << "pic_front:" << shmPicFront.mstrmsgname << "," << shmPicFront.mnBufferSize << "," << shmPicFront.mnBufferCount << std::endl; } } else { strmsgname = "picfront"; strncpy(shmPicFront.mstrmsgname,strmsgname.data(),255); shmPicFront.mnBufferSize = 10000000; shmPicFront.mnBufferCount = 1; } if(config["pic_rear"]) { if(config["pic_rear"]["msgname"]&&config["pic_rear"]["buffersize"]&&config["pic_rear"]["buffercount"]) { strmsgname = config["pic_rear"]["msgname"].as(); strncpy(shmPicRear.mstrmsgname,strmsgname.data(),255); shmPicRear.mnBufferSize = config["pic_rear"]["buffersize"].as(); shmPicRear.mnBufferCount = config["pic_rear"]["buffercount"].as(); std::cout << "pic_rear:" << shmPicRear.mstrmsgname << "," << shmPicRear.mnBufferSize << "," << shmPicRear.mnBufferCount << std::endl; } } else { strmsgname = "picrear"; strncpy(shmPicRear.mstrmsgname,strmsgname.data(),255); shmPicRear.mnBufferSize = 10000000; shmPicRear.mnBufferCount = 1; } if(config["pic_left"]) { if(config["pic_left"]["msgname"]&&config["pic_left"]["buffersize"]&&config["pic_left"]["buffercount"]) { strmsgname = config["pic_left"]["msgname"].as(); strncpy(shmPicLeft.mstrmsgname,strmsgname.data(),255); shmPicLeft.mnBufferSize = config["pic_left"]["buffersize"].as(); shmPicLeft.mnBufferCount = config["pic_left"]["buffercount"].as(); std::cout << "pic_left:" << shmPicLeft.mstrmsgname << "," << shmPicLeft.mnBufferSize << "," << shmPicLeft.mnBufferCount << std::endl; } } else { strmsgname = "picleft"; strncpy(shmPicLeft.mstrmsgname,strmsgname.data(),255); shmPicLeft.mnBufferSize = 10000000; shmPicLeft.mnBufferCount = 1; } if(config["pic_right"]) { if(config["pic_right"]["msgname"]&&config["pic_right"]["buffersize"]&&config["pic_right"]["buffercount"]) { strmsgname = config["pic_right"]["msgname"].as(); strncpy(shmPicRight.mstrmsgname,strmsgname.data(),255); shmPicRight.mnBufferSize = config["pic_right"]["buffersize"].as(); shmPicRight.mnBufferCount = config["pic_right"]["buffercount"].as(); std::cout << "pic_right:" << shmPicRight.mstrmsgname << "," << shmPicRight.mnBufferSize << "," << shmPicRight.mnBufferCount << std::endl; } } else { strmsgname = "picright"; strncpy(shmPicRight.mstrmsgname,strmsgname.data(),255); shmPicRight.mnBufferSize = 10000000; shmPicRight.mnBufferCount = 1; } if(config["chassis"]) { if(config["chassis"]["msgname"]&&config["chassis"]["buffersize"]&&config["chassis"]["buffercount"]) { strmsgname = config["chassis"]["msgname"].as(); strncpy(shmChassis.mstrmsgname,strmsgname.data(),255); shmChassis.mnBufferSize = config["chassis"]["buffersize"].as(); shmChassis.mnBufferCount = config["chassis"]["buffercount"].as(); std::cout << "chassis:" << shmChassis.mstrmsgname << "," << shmChassis.mnBufferSize << "," << shmChassis.mnBufferCount << std::endl; } } else { strmsgname = "chassis"; strncpy(shmChassis.mstrmsgname,strmsgname.data(),255); shmChassis.mnBufferSize = 10000; shmChassis.mnBufferCount = 1; } if(config["platform_feedback"]) { if(config["platform_feedback"]["msgname"]&&config["platform_feedback"]["buffersize"]&&config["platform_feedback"]["buffercount"]) { strmsgname = config["platform_feedback"]["msgname"].as(); strncpy(shmPlatformFeedback.mstrmsgname,strmsgname.data(),255); shmPlatformFeedback.mnBufferSize = config["platform_feedback"]["buffersize"].as(); shmPlatformFeedback.mnBufferCount = config["platform_feedback"]["buffercount"].as(); std::cout << "platform_feedback:" << shmPlatformFeedback.mstrmsgname << "," << shmPlatformFeedback.mnBufferSize << "," << shmPlatformFeedback.mnBufferCount << std::endl; } } else { strmsgname = "platformFeedback"; strncpy(shmPlatformFeedback.mstrmsgname,strmsgname.data(),255); shmPlatformFeedback.mnBufferSize = 10000; shmPlatformFeedback.mnBufferCount = 1; } if(config["GPS_IMU"]) { if(config["GPS_IMU"]["msgname"]&&config["GPS_IMU"]["buffersize"]&&config["GPS_IMU"]["buffercount"]) { strmsgname = config["GPS_IMU"]["msgname"].as(); strncpy(shmGPSIMU.mstrmsgname,strmsgname.data(),255); shmGPSIMU.mnBufferSize = config["GPS_IMU"]["buffersize"].as(); shmGPSIMU.mnBufferCount = config["GPS_IMU"]["buffercount"].as(); std::cout << "GPS_IMU:" << shmGPSIMU.mstrmsgname << "," << shmGPSIMU.mnBufferSize << "," << shmGPSIMU.mnBufferCount << std::endl; } } else { strmsgname = "hcp2_gpsimu"; strncpy(shmGPSIMU.mstrmsgname,strmsgname.data(),255); shmGPSIMU.mnBufferSize = 10000; shmGPSIMU.mnBufferCount = 1; } if(config["trace_map"]) { if(config["trace_map"]["msgname"]&&config["trace_map"]["buffersize"]&&config["trace_map"]["buffercount"]) { strmsgname = config["trace_map"]["msgname"].as(); strncpy(shmTraceMap.mstrmsgname,strmsgname.data(),255); shmTraceMap.mnBufferSize = config["trace_map"]["buffersize"].as(); shmTraceMap.mnBufferCount = config["trace_map"]["buffercount"].as(); std::cout << "trace_map:" << shmTraceMap.mstrmsgname << "," << shmTraceMap.mnBufferSize << "," << shmTraceMap.mnBufferCount << std::endl; } } else { strmsgname = "simpletrace"; strncpy(shmTraceMap.mstrmsgname,strmsgname.data(),255); shmTraceMap.mnBufferSize = 100000; shmTraceMap.mnBufferCount = 1; } if(config["xodr_request"]) { if(config["xodr_request"]["msgname"]&&config["xodr_request"]["buffersize"]&&config["xodr_request"]["buffercount"]) { strmsgname = config["xodr_request"]["msgname"].as(); strncpy(shmXodrRequest.mstrmsgname,strmsgname.data(),255); shmXodrRequest.mnBufferSize = config["xodr_request"]["buffersize"].as(); shmXodrRequest.mnBufferCount = config["xodr_request"]["buffercount"].as(); std::cout << "xodr_request:" << shmXodrRequest.mstrmsgname << "," << shmXodrRequest.mnBufferSize << "," << shmXodrRequest.mnBufferCount << std::endl; } } else { strmsgname = "xodrreq"; strncpy(shmXodrRequest.mstrmsgname,strmsgname.data(),255); shmXodrRequest.mnBufferSize = 1000; shmXodrRequest.mnBufferCount = 1; } return; } void DataExchangeClient::ListenFrontPicMsg(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname) // need a lock { iv::vision::rawpic xdata; if(!xdata.ParseFromArray(strdata,nSize)) { std::cout<<" ListenFrontPicMsg parese error."< simpletrace; simpletrace.clear(); simpletrace.resize(npoint); memcpy(simpletrace.data(),strdata,npoint*sizeof(iv::simpletrace)); org::jeecg::defsDetails::grpc::MapPoint onePoint; pathPoints.clear(); for(int i = 0;i < npoint;i++) { onePoint.set_index(i); onePoint.mutable_mappoint()->set_latitude(simpletrace[i].gps_lat); onePoint.mutable_mappoint()->set_longitude(simpletrace[i].gps_lng); pathPoints.append(onePoint); // std::cout<CopyFrom(positionFeedback); request.set_pitch(pitch); request.set_roll(roll); request.set_heading(heading); gMutex_GPSIMU.unlock(); gMutex_ImageFront.lock(); request.set_cameraimagefront(cameraImageFront.data(),cameraImageFront.size()); gMutex_ImageFront.unlock(); gMutex_ImageRear.lock(); request.set_cameraimagerear(cameraImageRear.data(),cameraImageRear.size()); gMutex_ImageRear.unlock(); gMutex_ImageLeft.lock(); request.set_cameraimageleft(cameraImageLeft.data(),cameraImageLeft.size()); gMutex_ImageLeft.unlock(); gMutex_ImageRight.lock(); request.set_cameraimageright(cameraImageRight.data(),cameraImageRight.size()); gMutex_ImageRight.unlock(); request.set_sensorstatusgpsimu(sensorStatusGPSIMU); request.set_sensorstatuslidar(sensorStatusLidar); request.set_sensorstatusradar(sensorStatusRadar); request.set_sensorstatuscamfront(sensorStatusCamFront); request.set_sensorstatuscamrear(sensorStatusCamRear); request.set_sensorstatuscamleft(sensorStatusCamLeft); request.set_sensorstatuscamright(sensorStatusCamRight); request.set_isarrived(isArrived); request.set_platenumber(plateNumber); request.set_usestatusfeedback(org::jeecg::defsDetails::grpc::UseStatus::ENABLING); request.set_remainpathlength(500.0); request.set_classfeedback(vehicleType); // Container for the data we expect from the server. ResponseMessage reply; // Context for the client. It could be used to convey extra information to // the server and/or tweak certain RPC behaviors. ClientContext context; gpr_timespec timespec; timespec.tv_sec = 2; timespec.tv_nsec = 0; timespec.clock_type = GPR_TIMESPAN; context.set_deadline(timespec); // The actual RPC. Status status = stub_ -> uploadVehicleInfo(&context, request, &reply); // Act upon its status. if (status.ok()) { destinationPosition.CopyFrom(reply.destinationposition()); emit destination_Recieved(); // std::cout<operator =(pathPoints.at(i)); } request.set_arrivedtime(500.0/gspeedWantAvg); request.set_waittime(gwaitTime); request.set_totalpathlength(500.0); // Container for the data we expect from the server. Empty reply; // Context for the client. It could be used to convey extra information to // the server and/or tweak certain RPC behaviors. ClientContext context; gpr_timespec timespec; timespec.tv_sec = 5; timespec.tv_nsec = 0; timespec.clock_type = GPR_TIMESPAN; context.set_deadline(timespec); // The actual RPC. Status status = stub_ -> uploadPath(&context,request,&reply); // Act upon its status. if (status.ok()) { if(reply.id() == gstrid) { std::cout<<"Path uploaded by car id:"< points) { id = gstrid; patrolPathID = pathID; pathPoints.clear(); for(int i = 0;i < points.size();i++) { pathPoints.append(points.value(i)); // std::cout<=interval) { uint64_t realInterval = abs(xTime.elapsed() - realLastTime); realLastTime = xTime.elapsed(); updateData(realInterval); std::string reply = uploadVehicleInfo(); // std::cout<< reply <= 2500) { if(mileageFile.open(QIODevice::WriteOnly | QIODevice::Text)) { QString strMileage = QString::number(mileage,'f',4); mileageFile.write(strMileage.toUtf8()); } mileageFile.flush(); mileageFile.close(); fileWriteTime = xTime.elapsed(); } else { std::this_thread::sleep_for(std::chrono::microseconds(500));//sleep 0.5ms } } } void DataExchangeClient::patrolPOI_Recieved_Slot(std::string pathID) { if(destinationRefreshed == false) { destinationRefreshed = true; patrolPathID = pathID; std::cout<<"patrol path calculating"< somePoints; // if(mapfile.open(QIODevice::ReadOnly | QIODevice::Text)) // { // while(!mapfile.atEnd()) // { // QByteArray line = mapfile.readLine(); // QString map_str(line); // QStringList oneline = map_str.split(","); // org::jeecg::defsDetails::grpc::MapPoint onePoint; // onePoint.set_index(oneline.at(0).toInt()); // onePoint.mutable_mappoint()->set_longitude(oneline.at(1).toDouble()); // onePoint.mutable_mappoint()->set_latitude(oneline.at(2).toDouble()); // onePoint.mutable_mappoint()->set_height(oneline.at(3).toDouble()); // somePoints.append(onePoint); // } // } // updatePath(pathID,somePoints); // uploadPath(); } void DataExchangeClient::ctrlMode_Changed_Slot(org::jeecg::defsDetails::grpc::CtrlMode ctrlMode) { modeFeedback = ctrlMode; } void DataExchangeClient::destination_Recieved_Slot(void) { if(fabs(destinationPosition.latitude()) > 0.000001 \ && fabs(destinationPosition.longitude()) > 0.000001) { if(destinationRefreshed == true) { xodrobj xodrDest; xodrDest.flon = destinationPosition.longitude(); xodrDest.flat = destinationPosition.latitude(); xodrDest.lane = 1; iv::modulecomm::ModuleSendMsg(shmXodrRequest.mpa,(char *)&xodrDest,sizeof(xodrobj)); // send request msg destinationRefreshed = false; } } } void DataExchangeClient::path_Updated_Slot(void) { uploadPath(); if(destinationRefreshed == true) destinationRefreshed = false; }