Parcourir la source

canbus数据库异步存储
localization pci通信代码bug优化

limengqi il y a 2 mois
Parent
commit
b42027249e
3 fichiers modifiés avec 45 ajouts et 30 suppressions
  1. 4 2
      src/canbus/canbus.cpp
  2. 34 26
      src/localization/localization.cpp
  3. 7 2
      src/localization/localization.h

+ 4 - 2
src/canbus/canbus.cpp

@@ -2752,7 +2752,8 @@ void Canbus::RackTestReplyDetailOnTimer(const ros::TimerEvent &event)
                                       task_id,rack_set_speed,rack_actual_speed,
                                       task_time_stamp_ui,over_speed_num,
                                       data_task_already_num);
-       thread_taskdataui.join();
+       //thread_taskdataui.join();
+       thread_taskdataui.detach();
     }
     else
     {
@@ -3147,7 +3148,8 @@ void Canbus::RTKLocationCallback(const localization::localMsg::ConstPtr& msg)
                                 requestBrk.uiBrkPsngCtrReq / 10,
                                 task_time_stamp,over_speed_num,
                                 data_task_already_num);
-    thread_taskdata.join();
+    //thread_taskdata.join();
+    thread_taskdata.detach();
 
   }
   catch (ros::Exception ex)

+ 34 - 26
src/localization/localization.cpp

@@ -274,12 +274,17 @@ if (car_input_mode == "modbus") {
     }
   }
 else if(car_input_mode == "pci"){
-    if (!ros::param::get("car_input_volspeed_max", car_input_volspeed_max))
-        car_input_volspeed_max = 100;
+  if (!ros::param::get("car_input_volspeed_max", car_input_volspeed_max)){
+    car_input_volspeed_max = 100;
+  }
+
+  rack_pci_timer_ = CreateTimer(ros::Duration(duration_pci),&Localization::RackPciOnTimer,this,false,false);
+  rack_pci_timer_.start();
+
   ros::Rate loop_rate(rate);
+
   while(ros::ok())
   {
-//    if (kbhit()) continue;
     if (!ACTS2110_AI_ReadAnalog(hDevice, fVoltArray, nReadSampsPerChan, &nSampsPerChanRead, &nReadableSamps, fTimeout))
     {
       LOG(ERROR) << Name() <<"PCI Read Data Timeout nSampsPerChanRead=" << nSampsPerChanRead;
@@ -287,10 +292,9 @@ else if(car_input_mode == "pci"){
     else{
       if (nSampsPerChanRead <= 0)
       {
+        //LOG(INFO) << Name() << "PCI nSampsPerChanRead= " << nSampsPerChanRead;
           continue;
-      }
-      //LOG(INFO) << Name() << "PCI nSampsPerChanRead= " << nSampsPerChanRead;
-      double voltage = 0;
+      }      
       for (U32 nIndex = 0; nIndex < 1; nIndex++)
       {
           for (nChannel = 0; nChannel < AIParam.nSampChanCount; nChannel++)
@@ -299,28 +303,9 @@ else if(car_input_mode == "pci"){
             printf("AI%02d=%.4f\t\n", nChannel, fVoltArray[nChannel + nIndex * AIParam.nSampChanCount]);
           }
       }
-      LOG(INFO) << Name() << "PCI voltage= " << voltage;
-      try{
-          localization::localMsg localization;
-          localization.Longitude =  0;
-          localization.Latitude = 0;
-          localization.Height = 0;
-          localization.AngleDeviated = 0;
-          int max = car_input_volspeed_max;
-          localization.Speed = max / 10 * voltage;
-          if(localization.Speed < 0.4)
-          {
-          localization.Speed = 0;
-          }
-          geometry_pub.publish(localization);
-          LOG(INFO) << Name() << " publish speed:" << std::setprecision(4) << localization.Speed;
-      }
-      catch (ros::Exception ex) {
-          LOG(ERROR)<<Name()<< "PCI publish speed error: " << ex.what();
-      }
+      //LOG(INFO) << Name() << "PCI voltage= " << voltage;
     }
     ros::spinOnce();
-    loop_rate.sleep();
   }
 }
   //TODO
@@ -372,6 +357,29 @@ int Localization::read_txt(string &path)
    myfile.close();
    return ROBOT_SUCCESS;
 }
+
+void Localization::RackPciOnTimer(const ros::TimerEvent &event)
+{
+  try{
+      localization::localMsg localization;
+      localization.Longitude =  0;
+      localization.Latitude = 0;
+      localization.Height = 0;
+      localization.AngleDeviated = 0;
+      int max = car_input_volspeed_max;
+      localization.Speed = max / 10 * voltage;
+      if(localization.Speed < 0.4)
+      {
+      localization.Speed = 0;
+      }
+      geometry_pub.publish(localization);
+      //LOG(INFO) << Name() << " publish speed:" << std::setprecision(4) << localization.Speed;
+  }
+  catch (ros::Exception ex) {
+      LOG(ERROR)<<Name()<< "PCI publish speed error: " << ex.what();
+  }
+}
+
 bool Localization::IsOpen()
 {
   //检测串口是否已经打开,并给出提示信息

+ 7 - 2
src/localization/localization.h

@@ -148,7 +148,7 @@ private:
   unsigned char modbus_recv[11];
   //----------
   //---测试用
-  const double duration_rack = 0.1;//5ms//台架测试任务执行时间
+  const double duration_rack = 0.1;//100ms//台架测试任务执行时间
   ros::Timer rack_test_timer_;    //台架测试任务定时器
   void RackTestOnTimer(const ros::TimerEvent &event);  //台架测试任务定时器回调函数
   //---测试用
@@ -165,7 +165,12 @@ private:
   HANDLE hDevice = NULL;
   ACTS2110_MAIN_INFO MainInfo;
   U32 nChannel = 0;
-  F64 fSampleRate = 50000.0;  //100sps = 100Hz
+  F64 fSampleRate = 50000.0;  //50000sps = 50000Hz
+  double voltage = 0;
+
+  const double duration_pci = 0.01;//10ms//pci模拟量采集后发布速度时间
+  ros::Timer rack_pci_timer_;    //pci模拟量采集后发布速度定时器
+  void RackPciOnTimer(const ros::TimerEvent &event);  //pci模拟量采集后发布速度定时器回调函数
 
 };