Просмотр исходного кода

change some code for autoware test, not complete.

yuchuli 1 год назад
Родитель
Сommit
71c2e31271

+ 5 - 0
src/decition/decition_fromautoware/ctrlcmd2decition.cpp

@@ -122,6 +122,11 @@ void ctrlcmd2decition::ListenCtrlCmd(const char *strdata, const unsigned int nSi
             fbrake = facc;
             ftorque = 0;
         }
+        if((xctrlcmd.linear_velocity()<(mfVelNow - 0.01)) && (facc <0))
+        {
+            fbrake = facc;
+            ftorque = 0;
+        }
     }
 //    facc = xctrlcmd.linear_acceleration();
     fwheelangle = xctrlcmd.steering_angle() * (180.0/M_PI) * 15.0;

+ 1 - 0
src/detection/detection_chassis/decodechassis.cpp

@@ -510,6 +510,7 @@ int ProcShenLanCANFDChassis(void *pa, iv::can::canmsg *pmsg)
                 vehspeed = static_cast<double>(value) * 0.05625;
 
                 xchassis.set_vel(static_cast<float>(vehspeed));
+                xchassis.set_time(std::chrono::system_clock::now().time_since_epoch().count());
 
                 ShareChassis(pa,&xchassis);
                 xchassis.clear_angle_feedback();

+ 22 - 2
src/ros2/src/pilot_autoware_bridge/src/pilot_autoware_bridge_core.cpp

@@ -39,6 +39,8 @@
 //#include "modulecomm.h"   
 using namespace std;
 
+static double gfchassis_acc = 0;
+
 
 pilot_autoware_bridge::pilot_autoware_bridge() : Node("pilot_autoware_bridge")
 {
@@ -273,7 +275,7 @@ void pilot_autoware_bridge::callbackTimerGPS()
             double flat = xgpsimu.lat();
             double flon = xgpsimu.lon();
 
-            mfacc = xgpsimu.acce_x();
+            mfacc = gfchassis_acc;//xgpsimu.acce_x();
 
             double pitch,roll,yaw;
             pitch = 0;
@@ -331,6 +333,7 @@ void pilot_autoware_bridge::callbackTimerGPS()
     int nochassiscount = 0;
 
     nread = mpsharechassis->read(strdata,10000);
+    
 
     if(nread < 1)
     {
@@ -343,6 +346,8 @@ void pilot_autoware_bridge::callbackTimerGPS()
     }
     else
     {
+        static int64_t nchassislast = 0;
+        static double fchassis_veh_last = 0;
         iv::chassis xchassis;
         //    static int ncount = 0;
         if(!xchassis.ParseFromArray(strdata,nread))
@@ -352,6 +357,21 @@ void pilot_autoware_bridge::callbackTimerGPS()
         else
         {
             steear_now = (xchassis.angle_feedback() *M_PI/180.0)/15.0;
+            double fchassis_veh_now = xchassis.vel()/3.6;
+            int64_t nchassis_now = xchassis.time();
+            int64_t ndiff = nchassis_now - nchassislast;
+            double fdiff = ndiff/1e9;
+            if(fdiff > 0)
+            {
+                gfchassis_acc = (fchassis_veh_now - fchassis_veh_last) /fdiff;
+                std::cout<<" acc: "<<gfchassis_acc<<std::endl;
+            }
+            else
+            {
+                gfchassis_acc = 0;
+            }
+            nchassislast = nchassis_now;
+            fchassis_veh_last = fchassis_veh_now;
             nochassiscount = 0;
   //          std::cout<<" steer : "<<steear_now<<std::endl;
         }
@@ -531,7 +551,7 @@ void pilot_autoware_bridge::UpdateGPSIMU(const char * strdata,const unsigned int
     double flat = xgpsimu.lat();
     double flon = xgpsimu.lon();
 
-    mfacc = xgpsimu.acce_x();
+    mfacc = gfchassis_acc; //xgpsimu.acce_x();
 
     double pitch,roll,yaw;
     pitch = 0;