2 Commits 65aaadeebc ... bfeb284491

Author SHA1 Message Date
  limengqi bfeb284491 修改模拟量通信部分代码 3 months ago
  limengqi 67dd305847 注释板卡CAN和模拟量命令行配置代码 3 months ago
3 changed files with 7 additions and 7 deletions
  1. 3 3
      src/canbus/canbus.cpp
  2. 2 2
      src/localization/localization.cpp
  3. 2 2
      src/localization/localization.h

+ 3 - 3
src/canbus/canbus.cpp

@@ -3166,10 +3166,10 @@ void Canbus::RTKLocationCallback(const localization::localMsg::ConstPtr& msg)
 int Canbus::can_init_for_linux(int *fd)
 int Canbus::can_init_for_linux(int *fd)
 {
 {
     //0、设置can通信波特率
     //0、设置can通信波特率
-    system("sudo ip link set can0 down");
+//    system("sudo ip link set can0 down");
     //波特率设置为500Kbps
     //波特率设置为500Kbps
-    system("sudo ip link set can0 type can bitrate 500000 triple-sampling on");
-    system("sudo ip link set can0 up");
+//    system("sudo ip link set can0 type can bitrate 500000 triple-sampling on");
+//    system("sudo ip link set can0 up");
 
 
     int ret = 0;
     int ret = 0;
     //1、创建socket can套接字
     //1、创建socket can套接字

+ 2 - 2
src/localization/localization.cpp

@@ -69,7 +69,7 @@ int Localization::Init() {
   }
   }
   else if(car_input_mode == "pci")
   else if(car_input_mode == "pci")
   {
   {
-system("sudo chmod 666 /dev/acts2110-0");
+//system("sudo chmod 666 /dev/acts2110-0");
    // 第一步 创建设备对象
    // 第一步 创建设备对象
     hDevice = ACTS2110_DEV_Create(0, 0);
     hDevice = ACTS2110_DEV_Create(0, 0);
     if (hDevice == NULL)
     if (hDevice == NULL)
@@ -279,7 +279,7 @@ else if(car_input_mode == "pci"){
   ros::Rate loop_rate(rate);
   ros::Rate loop_rate(rate);
   while(ros::ok())
   while(ros::ok())
   {
   {
-    if (kbhit()) continue;
+//    if (kbhit()) continue;
     if (!ACTS2110_AI_ReadAnalog(hDevice, fVoltArray, nReadSampsPerChan, &nSampsPerChanRead, &nReadableSamps, fTimeout))
     if (!ACTS2110_AI_ReadAnalog(hDevice, fVoltArray, nReadSampsPerChan, &nSampsPerChanRead, &nReadableSamps, fTimeout))
     {
     {
       LOG(ERROR) << Name() <<"PCI Read Data Timeout nSampsPerChanRead=" << nSampsPerChanRead;
       LOG(ERROR) << Name() <<"PCI Read Data Timeout nSampsPerChanRead=" << nSampsPerChanRead;

+ 2 - 2
src/localization/localization.h

@@ -155,12 +155,12 @@ private:
   //_____
   //_____
 
 
   //----------pci
   //----------pci
-  #define CH_PERCHAN 102400
+  #define CH_PERCHAN 1
   F64 fVoltArray[CH_PERCHAN];
   F64 fVoltArray[CH_PERCHAN];
   ACTS2110_AI_PARAM AIParam;
   ACTS2110_AI_PARAM AIParam;
   U32 nReadSampsPerChan = CH_PERCHAN;	// 每通道读取点数
   U32 nReadSampsPerChan = CH_PERCHAN;	// 每通道读取点数
   U32 nSampsPerChanRead = 0;
   U32 nSampsPerChanRead = 0;
-  F64 fTimeout = 1.0; // 1秒钟超时
+  F64 fTimeout = 1; // 1秒钟超时
   U32 nReadableSamps = 0;
   U32 nReadableSamps = 0;
   HANDLE hDevice = NULL;
   HANDLE hDevice = NULL;
   ACTS2110_MAIN_INFO MainInfo;
   ACTS2110_MAIN_INFO MainInfo;