|
@@ -15,6 +15,8 @@ simplesmshare * gpsharectrlcmd;
|
|
|
|
|
|
bool gbthreadrun = true;
|
|
|
|
|
|
+#include <iostream>
|
|
|
+
|
|
|
void UpdateChassis(const char *strdata, const unsigned int nSize, const unsigned int index, const QDateTime *dt, const char *strmemname)
|
|
|
{
|
|
|
(void)index;
|
|
@@ -33,12 +35,14 @@ void ListenRaw(const char * strdata,const unsigned int nSize,const unsigned int
|
|
|
(void)dt;
|
|
|
(void)strmemname;
|
|
|
|
|
|
+ std::cout<<" recv gps."<<std::endl;
|
|
|
+
|
|
|
gpsharegps->write(strdata,nSize);
|
|
|
|
|
|
|
|
|
}
|
|
|
|
|
|
-void treadupdatectrl()
|
|
|
+void threadupdatectrl()
|
|
|
{
|
|
|
char * strdata;
|
|
|
int nbufsize = 10000;
|
|
@@ -48,7 +52,7 @@ void treadupdatectrl()
|
|
|
int nread = gpsharectrlcmd->read(strdata,nbufsize);
|
|
|
if(nread > 0)
|
|
|
{
|
|
|
- iv::modulecomm::ModuleSendMsg(gpactrlcmd,strdata,nbufsize);
|
|
|
+ iv::modulecomm::ModuleSendMsg(gpactrlcmd,strdata,nread);
|
|
|
}
|
|
|
std::this_thread::sleep_for(std::chrono::milliseconds(1));
|
|
|
}
|
|
@@ -74,5 +78,7 @@ int main(int argc, char *argv[])
|
|
|
gpachassis = iv::modulecomm::RegisterRecv("chassis",UpdateChassis);
|
|
|
gpactrlcmd = iv::modulecomm::RegisterSend("ctrlcmd",10000,1);
|
|
|
|
|
|
+ std::thread * pthread = new std::thread(threadupdatectrl);
|
|
|
+
|
|
|
return a.exec();
|
|
|
}
|