#ifndef COMPUTEWAYPOINTS_H #define COMPUTEWAYPOINTS_H #include #include #include #include #include "math/gnss_coordinate_convert.h" #include "gpsimu.pb.h" #include "mapdata.pb.h" #include "modulecomm.h" class ComputeWayPoints { public: ComputeWayPoints(); ~ComputeWayPoints(); private: iv::gps::gpsimu mgpsimu; QMutex mMutexgpsimu; bool mbGPSIMUUpdate = false; iv::map::tracemap mtracemap; QMutex mMutexTraceMap; bool mbHaveMap = false; QMutex mMutexWait; QWaitCondition mwc; bool mbCompute = true; void ThreadCompute(); std::thread * mpthread; void ListenGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname); void ListenNewTraceMap(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname); int FindWayPoints(iv::map::tracemap & xtracemap); void * mpagpsimu; void * mpanewtrace; void * mpawaypoints; double mfVel = 15.0; }; #endif // COMPUTEWAYPOINTS_H