Browse Source

test autoware run .ok.

yuchuli 1 year ago
parent
commit
f764f87ba4

+ 8 - 2
src/driver/driver_pilotautoware/main.cpp

@@ -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();
 }

+ 4 - 1
src/driver/driver_pilotautoware/simplesmshare.cpp

@@ -58,6 +58,8 @@ bool simplesmshare::write(const char * strdata,int nsize)
     memcpy(pdata,strdata,nsize);
     *pmark = 0;
 
+    std::cout<<"write msg. "<<std::endl;
+
     return true;
 }
 
@@ -94,7 +96,8 @@ int simplesmshare::read(char * strdata,unsigned int nreadmax)
          return 0;
      }
 
-     if(abs(*ptime -nLastUpdate)/1000000 > 30000)
+     int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count();
+     if(abs(*ptime -nnow)/1000000 > 30000)
      {
          std::cout<<" data is more than 30 seconds."<<std::endl;
          return 0;

+ 1 - 0
src/ros2/src/pilot_autoware_bridge/src/pilot_autoware_bridge_core.cpp

@@ -327,6 +327,7 @@ void pilot_autoware_bridge::callbackTimerGPS()
     else
     {
         steear_now = (xchassis.angle_feedback() *M_PI/180.0)/15.0;
+        std::cout<<" steer : "<<steear_now<<std::endl;
     }
 
   }