Browse Source

complete adciv_maketool. and add createmaketool.sh for build adciv_maketool. and add ros2 program adc_can_nvidia_agx.

yuchuli 1 year ago
parent
commit
5719c79fa3

+ 80 - 0
createmaketool.sh

@@ -0,0 +1,80 @@
+qtmake=" "
+
+
+if [ ${#qtmake} -lt 5 ]; then
+  optfiles=`find /usr/lib/x86_64-linux-gnu -name 'qmake'` 
+  for entry in $optfiles
+  do
+     x=${entry:0-14:14}
+     if [ "$x" == "/qt5/bin/qmake" ];  then
+        qtmake="$entry"
+	echo "  -----find qmake"
+	echo "$qtmake"
+     fi
+  done
+fi
+
+if [ ${#qtmake} -lt 5 ]; then
+  echo "maybe agx,find qmake in usr folder "
+  optfiles=`find /usr/lib/aarch64-linux-gnu -name 'qmake'` 
+  for entry in $optfiles
+  do
+     x=${entry:0-14:14}
+     if [ "$x" == "/qt5/bin/qmake" ];  then
+        qtmake="$entry"
+	echo "  -----find qmake"
+	echo "$qtmake"
+     fi
+  done
+fi
+
+if [ ${#qtmake} -lt 5 ]; then
+  echo "find in /usr folder "
+  optfiles=`find /usr -name 'qmake'` 
+  for entry in $optfiles
+  do
+     x=${entry:0-14:14}
+     if [ "$x" == "/qt5/bin/qmake" ];  then
+        qtmake="$entry"
+	echo "  -----find qmake"
+	echo "$qtmake"
+     fi
+  done
+fi
+
+if [ ${#qtmake} -lt 5 ]; then
+  echo "find in /opt folder "
+  optfiles=`find /opt -name 'qmake'` 
+  for entry in $optfiles
+  do
+     x=${entry:0-17:17}
+     if [ "$x" == "/gcc_64/bin/qmake" ];  then
+        qtmake="$entry"
+	echo "  -----find qmake"
+	echo "$qtmake"
+     fi
+  done
+fi
+
+if [ ${#qtmake} -lt 5 ]; then
+	echo "fail to find qmake.No qmake in /usr or /opt directory. You can munual set qmake."
+	
+else
+	echo "---qmake---:""$qtmake"
+fi
+
+cpu_num=`cat /proc/stat | grep cpu[0-9] -c`
+
+cd src/tool/adciv_maketool
+$qtmake adciv_maketool.pro
+make -j${cpu_num}
+make clean
+cp adciv_maketool ./../../../
+rm Makefile
+rm .qmake.stash
+cd ../../../
+
+
+
+
+

+ 71 - 0
src/ros2/src/adc_can_nvidia_agx/CMakeLists.txt

@@ -0,0 +1,71 @@
+cmake_minimum_required(VERSION 3.14)
+project(adc_can_nvidia_agx)
+
+find_package(autoware_cmake REQUIRED)
+autoware_package()
+
+
+#Default to C++14
+if(NOT CMAKE_CXX_STANDARD)
+  set(CMAKE_CXX_STANDARD 14)
+endif()
+
+if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
+  add_compile_options(-Wall -Wextra -Wpedantic)
+endif()
+
+
+find_package(ament_cmake REQUIRED)
+find_package(rclcpp REQUIRED)
+find_package(std_msgs REQUIRED)
+find_package(geometry_msgs REQUIRED)
+find_package(nav_msgs REQUIRED) 
+find_package(sensor_msgs REQUIRED)
+find_package(tf2_geometry_msgs REQUIRED)
+find_package(autoware_auto_control_msgs REQUIRED)
+
+find_package(Qt5 COMPONENTS Core Widgets REQUIRED)
+
+find_package(Protobuf REQUIRED)
+
+
+include_directories(
+##  INCLUDE_DIRS include
+  ${CMAKE_CURRENT_BINARY_DIR}/..
+  ${catkin_INCLUDE_DIRS} include
+)
+
+include_directories(
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include
+  ${CMAKE_CURRENT_SOURCE_DIR}/../include/adc_can_nvidia_agx
+)
+link_directories(
+  ${CMAKE_CURRENT_SOURCE_DIR}/../lib
+)
+
+
+add_executable(adc_can_nvidia_agx
+  src/adc_can_nvidia_agx_node.cpp
+  src/adc_can_nvidia_agx_core.cpp
+  src/basecan.cpp
+  src/canctrl.cpp
+  src/nvcan.cpp
+)
+
+#target_link_libraries(adc_can_nvidia_agx  ${Protobuf_LIBRARIES}  Geographic )  
+# modulecomm 
+
+ament_target_dependencies(adc_can_nvidia_agx rclcpp std_msgs geometry_msgs 
+  tf2_geometry_msgs nav_msgs sensor_msgs can_msgs autoware_auto_control_msgs autoware_auto_geometry_msgs
+  autoware_auto_mapping_msgs autoware_auto_planning_msgs autoware_auto_vehicle_msgs
+  tier4_autoware_utils  autoware_auto_perception_msgs
+  tier4_perception_msgs)
+
+
+install(TARGETS
+adc_can_nvidia_agx
+  DESTINATION lib/${PROJECT_NAME})
+
+ament_package()
+
+

+ 31 - 0
src/ros2/src/adc_can_nvidia_agx/README.md

@@ -0,0 +1,31 @@
+# pilot_autoware_bridge
+
+## Purpose
+
+This `pilot_autoware_bridge` is a bridge between pilot and autoware.
+
+
+
+## Inputs / Outputs
+
+### Input
+
+| Name | Type                            | Description                                       |
+| ---- | ------------------------------- | ------------------------------------------------- |
+| pose | geometry_msgs::msg::PoseStamped | pose source to used for the velocity calculation. |
+
+### Output
+
+| Name      | Type                                  | Description                                   |
+| --------- | ------------------------------------- | --------------------------------------------- |
+| twist     | geometry_msgs::msg::TwistStamped      | twist calculated from the input pose history. |
+| linear_x  | tier4_debug_msgs::msg::Float32Stamped | linear-x field of the output twist.           |
+| angular_z | tier4_debug_msgs::msg::Float32Stamped | angular-z field of the output twist.          |
+
+## Parameters
+
+none.
+
+## Assumptions / Known limits
+
+none.

+ 42 - 0
src/ros2/src/adc_can_nvidia_agx/include/adc_can_nvidia_agx/adc_can_nvidia_agx_core.hpp

@@ -0,0 +1,42 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#ifndef PILOT_AUTOWARE_BRIDGE_CORE_HPP_
+#define PILOT_AUTOWARE_BRIDGE_CORE_HPP_
+
+#include <rclcpp/rclcpp.hpp>
+
+#include "can_msgs/msg/frame.hpp"
+
+#include <string>
+
+
+class adc_can_nvidia_agx : public rclcpp::Node
+{
+public:
+    adc_can_nvidia_agx();
+    ~adc_can_nvidia_agx() = default;
+
+private:
+
+
+
+private:
+    std::string simulated_frame_id_;  //!< @brief simulated vehicle frame id
+    std::string origin_frame_id_;     //!< @brief map frame_id
+
+
+};
+
+#endif  

+ 34 - 0
src/ros2/src/adc_can_nvidia_agx/include/adc_can_nvidia_agx/basecan.h

@@ -0,0 +1,34 @@
+#ifndef BASECAN_H
+#define BASECAN_H
+
+#include <QThread>
+
+
+class basecan_msg
+{
+  public:
+    unsigned int id;
+    bool isExtern;
+    bool isRemote;
+    unsigned char nLen;
+    unsigned char data[64];
+};
+
+class basecan : public QThread
+{
+    Q_OBJECT
+public:
+    basecan();
+    ~basecan();
+    virtual int GetMessage(const int nch,basecan_msg * pMsg,const int nCap);
+    virtual int SetMessage(const int nch,basecan_msg * pMsg); //Send Message
+
+    virtual void startdev();
+    virtual void stopdev();
+
+signals:
+    void SIG_CANOPENSTATE(bool bCAN,int nR,const char * strres);
+    void SIGTEST();
+};
+
+#endif // BASECAN_H

+ 49 - 0
src/ros2/src/adc_can_nvidia_agx/include/adc_can_nvidia_agx/canctrl.h

@@ -0,0 +1,49 @@
+#ifndef CANCTRL_H
+#define CANCTRL_H
+
+#include <QThread>
+#include <QMutex>
+#include <memory>
+#include <QTimer>
+#include <array>
+#include <vector>
+#include <iostream>
+#include "nvcan.h"
+
+
+class canctrl : public QThread
+{
+    Q_OBJECT
+public:
+    canctrl(const char * strmemsend0,const char * strmemsend1,const char * strmemrecv0,const char * strmemrecv1);
+    ~canctrl();
+
+private slots:
+    void onCANState(bool bCAN,int nR,const char * strres);
+
+private:
+    void run();
+
+    basecan * mpcan;
+    std::shared_ptr<basecan> mspcan;
+    bool mbCANOpen = false;
+
+    std::vector<basecan_msg> msendmsgvector1;
+    std::vector<basecan_msg> msendmsgvector2;
+    const int SENDMSGBUFSIZE = 3000;
+
+    QMutex mMutexcan1;
+    QMutex mMutexcan2;
+
+    int mindex[2];
+
+    void * mpasend0, * mpasend1, * mparecv0, * mparecv1, *mpcanState;
+
+public:
+ //   void sendmsg(int index,iv::can::canmsg xmsg);
+    void sharecanmsg(void * xpa,basecan_msg * pxmsg,int ncount,int nch);
+
+
+};
+
+#endif // CANCTRL_H

+ 38 - 0
src/ros2/src/adc_can_nvidia_agx/include/adc_can_nvidia_agx/nvcan.h

@@ -0,0 +1,38 @@
+#ifndef NVCAN_H
+#define NVCAN_H
+#include "basecan.h"
+
+#include <vector>
+#include <QMutex>
+
+#include <thread>
+
+class nvcan : public basecan
+{
+    Q_OBJECT
+public:
+    nvcan();
+public:
+    void startdev();
+    void stopdev();
+
+    int GetMessage(const int nch,basecan_msg * pMsg,const int nCap);
+    int SetMessage(const int nch,basecan_msg * pMsg);
+
+private slots:
+    void onMsg(bool bCAN,int nR,const char * strres);
+
+private:
+    void run();
+    std::vector<basecan_msg> mMsgRecvBuf[2];
+
+    std::vector<basecan_msg> mMsgSendBuf[2];
+
+    QMutex mMutex;
+
+    bool mbCANOpen = false;
+    bool mbRunning = false;
+    int mnDevNum;
+};
+
+#endif // NVCAN_H

+ 9 - 0
src/ros2/src/adc_can_nvidia_agx/launch/adc_can_nvidia_agx.xml

@@ -0,0 +1,9 @@
+<launch>
+  <arg name="input_pose_topic" default="/localization/pose_estimator/pose" description=""/>
+  <arg name="output_twist_topic" default="/estimate_twist" description=""/>
+
+  <node pkg="testpose" exec="testpose" name="testpose" output="log">
+    <remap from="pose" to="$(var input_pose_topic)"/>
+    <remap from="twist" to="$(var output_twist_topic)"/>
+  </node>
+</launch>

+ 34 - 0
src/ros2/src/adc_can_nvidia_agx/package.xml

@@ -0,0 +1,34 @@
+<?xml version="1.0"?>
+<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
+<package format="3">
+  <name>adc_can_nvidia_agx</name>
+  <version>0.1.0</version>
+  <description>NVIDIA AGX CAN Driver for ros2</description>
+  <maintainer email="yuchuli@catarc.ac.cn">Yu Chuli</maintainer>
+  <license>Apache License 2.0</license>
+  <author email="yuchuli@catarc.ac.cn">Yu Chuli</author>
+
+  <buildtool_depend>ament_cmake</buildtool_depend>
+
+  <depend>autoware_auto_control_msgs</depend>
+  <depend>autoware_auto_mapping_msgs</depend>
+  <depend>autoware_auto_planning_msgs</depend>
+  <depend>autoware_auto_tf2</depend>
+  <depend>autoware_auto_vehicle_msgs</depend>
+
+    <depend>tier4_api_utils</depend>
+  <depend>tier4_autoware_utils</depend>
+  <depend>tier4_external_api_msgs</depend>
+  <depend>tier4_vehicle_msgs</depend>
+  <depend>tier4_perception_msgs</depend>
+  <depend>geometry_msgs</depend>
+  <depend>nav_msgs</depend>
+  <depend>sensor_msgs</depend>
+  <depend>can_msgs</depend>
+  <depend>rclcpp</depend>
+
+
+ <export>
+   <build_type>ament_cmake</build_type>
+ </export>
+</package>

+ 55 - 0
src/ros2/src/adc_can_nvidia_agx/src/adc_can_nvidia_agx_core.cpp

@@ -0,0 +1,55 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "adc_can_nvidia_agx/adc_can_nvidia_agx_core.hpp"
+
+#ifdef ROS_DISTRO_GALACTIC
+#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
+#else
+#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
+#endif
+
+#include <cmath>
+#include <cstddef>
+#include <functional>
+
+#include <time.h>
+#include <sstream>
+
+#include <iostream>
+
+#include <GeographicLib/MGRS.hpp>
+#include <GeographicLib/UTMUPS.hpp>
+
+#include <QString>
+
+//#include "modulecomm.h"   
+using namespace std;
+
+
+adc_can_nvidia_agx::adc_can_nvidia_agx() : Node("adc_can_nvidia_agx")
+{
+
+
+    simulated_frame_id_ = declare_parameter("simulated_frame_id", "base_link");
+    origin_frame_id_ = declare_parameter("origin_frame_id", "map");
+
+    static constexpr std::size_t queue_size = 1;
+    rclcpp::QoS durable_qos(queue_size);
+    durable_qos.transient_local();
+
+
+
+}
+

+ 29 - 0
src/ros2/src/adc_can_nvidia_agx/src/adc_can_nvidia_agx_node.cpp

@@ -0,0 +1,29 @@
+// Copyright 2015-2019 Autoware Foundation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+//     http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+
+#include "adc_can_nvidia_agx/adc_can_nvidia_agx_core.hpp"
+
+#include <rclcpp/rclcpp.hpp>
+
+#include <memory>
+
+int main(int argc, char ** argv)
+{
+  rclcpp::init(argc, argv);
+
+  rclcpp::spin(std::make_shared<adc_can_nvidia_agx>());
+  rclcpp::shutdown();
+
+  return 0;
+}

+ 37 - 0
src/ros2/src/adc_can_nvidia_agx/src/basecan.cpp

@@ -0,0 +1,37 @@
+#include "adc_can_nvidia_agx/basecan.h"
+
+basecan::basecan()
+{
+
+}
+
+basecan::~basecan()
+{
+    qDebug(" del basecan");
+}
+
+int basecan::GetMessage(const int nch,basecan_msg *pMsg, const int nCap)
+{
+    (void)nch;
+    (void)pMsg;
+    (void)nCap;
+    return 0;
+}
+
+int basecan::SetMessage(const int nch, basecan_msg *pMsg)
+{
+    (void)nch;
+    (void)pMsg;
+    return 0;
+}
+
+
+void basecan::startdev()
+{
+
+}
+
+void basecan::stopdev()
+{
+
+}

+ 118 - 0
src/ros2/src/adc_can_nvidia_agx/src/canctrl.cpp

@@ -0,0 +1,118 @@
+#include "adc_can_nvidia_agx/canctrl.h"
+
+#include <memory>
+
+#include <QTime>
+
+canctrl * gc;
+
+
+
+
+canctrl::canctrl(const char * strmemsend0,const char * strmemsend1,const char * strmemrecv0,const char * strmemrecv1)
+{
+
+    (void)strmemrecv0;
+    (void)strmemrecv1;
+    (void)strmemsend0;
+    (void)strmemsend1;
+    gc = this;
+
+    mpcan = new nvcan();
+    mspcan.reset(mpcan);
+    connect(mpcan,SIGNAL(SIG_CANOPENSTATE(bool,int,const char*)),this,SLOT(onCANState(bool,int,const char*)));
+    mpcan->startdev();
+}
+
+canctrl::~canctrl()
+{
+    mpcan->stopdev();
+
+    delete mpcan;
+
+
+
+}
+
+void canctrl::run()
+{
+
+
+
+    int nOldTime =  std::chrono::system_clock::now().time_since_epoch().count()/1000000;
+    int i;
+    (void)nOldTime;
+
+
+    while(!isInterruptionRequested())
+    {
+        if(mbCANOpen)
+        {
+            basecan_msg xmsg[2500];
+            int nRec1,nRec2,nSend1,nSend2;
+            (void)nSend1;
+            (void)nSend2;
+            if((nRec1 =mpcan->GetMessage(0,xmsg,2500))>0)
+            {
+                sharecanmsg(mparecv0,xmsg,nRec1,0);
+            }
+
+            if((nRec2 =mpcan->GetMessage(1,xmsg,2500))>0)
+            {
+                sharecanmsg(mparecv1,xmsg,nRec2,1);
+            }
+
+
+            nSend1 = 0;
+            nSend2 = 0;
+
+            mMutexcan1.lock();
+            for(i=0;i<static_cast<int>( msendmsgvector1.size());i++)
+            {
+                mpcan->SetMessage(0,&(msendmsgvector1.at(i)));
+            }
+            msendmsgvector1.clear();
+            mMutexcan1.unlock();
+
+            mMutexcan2.lock();
+            for(i=0; i<static_cast<int>(msendmsgvector2.size());i++)
+            {
+                mpcan->SetMessage(1,&(msendmsgvector2.at(i)));
+            }
+            msendmsgvector2.clear();
+            mMutexcan2.unlock();
+
+
+            msleep(1);
+        }
+        else
+        {
+
+            msleep(1);
+
+            std::cout<<" open can fail."<<std::endl;
+
+        }
+//        mpcan->mfault->SetFaultState(0, 0, "ok");
+    }
+
+    qDebug("thread canctrl complete.");
+
+}
+
+void canctrl::onCANState(bool bCAN, int nR, const char *strres)
+{
+    (void)nR;
+    mbCANOpen = bCAN;
+
+    std::cout<<" canstate is : "<<strres<<std::endl;
+}
+
+
+void canctrl::sharecanmsg(void *xpa, basecan_msg * pxmsg,int ncount,int nch)
+{
+    (void)xpa;
+    (void)pxmsg;
+    (void)ncount;
+    (void)nch;
+}

+ 352 - 0
src/ros2/src/adc_can_nvidia_agx/src/nvcan.cpp

@@ -0,0 +1,352 @@
+#include "adc_can_nvidia_agx/nvcan.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <stdint.h>
+#include <unistd.h>
+#include <string.h>
+#include <signal.h>
+#include <ctype.h>
+#include <libgen.h>
+#include <time.h>
+#include <errno.h>
+
+#include <sys/time.h>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <sys/uio.h>
+#include <net/if.h>
+
+
+#include <linux/can.h>
+#include <linux/can/raw.h>
+
+#include <QDateTime>
+
+#include <iostream>
+
+/* for hardware timestamps - since Linux 2.6.30 */
+#ifndef SO_TIMESTAMPING
+#define SO_TIMESTAMPING 37
+#endif
+
+/* from #include <linux/net_tstamp.h> - since Linux 2.6.30 */
+#define SOF_TIMESTAMPING_SOFTWARE (1<<4)
+#define SOF_TIMESTAMPING_RX_SOFTWARE (1<<3)
+#define SOF_TIMESTAMPING_RAW_HARDWARE (1<<6)
+
+#define MAXSOCK 16    /* max. number of CAN interfaces given on the cmdline */
+#define MAXIFNAMES 30 /* size of receive name index to omit ioctls */
+#define MAXCOL 6      /* number of different colors for colorized output */
+#define ANYDEV "any"  /* name of interface to receive from any CAN interface */
+#define ANL "\r\n"    /* newline in ASC mode */
+
+#define SILENT_INI 42 /* detect user setting on commandline */
+#define SILENT_OFF 0  /* no silent mode */
+#define SILENT_ANI 1  /* silent mode with animation */
+#define SILENT_ON  2  /* silent mode (completely silent) */
+
+#include <QTime>
+
+#define BUF_SIZE 1000
+
+std::string CANNAME[] = {"can0","can1"};
+
+nvcan::nvcan()
+{
+//    qDebug("nvcan");
+//    connect(this,SIGNAL(SIG_CANOPENSTATE(bool,int,const char*)),this,SLOT(onMsg(bool,int,const char*)));
+
+
+
+
+}
+
+void nvcan::run()
+{
+
+    int currmax = 2;
+    fd_set rdfs;
+    int s[MAXSOCK];
+    int ret;
+
+    int canfd_on = 1;
+    
+    struct sockaddr_can addr;
+    char ctrlmsg[CMSG_SPACE(sizeof(struct timeval) + 3*sizeof(struct timespec) + sizeof(__u32))];
+    struct iovec iov;
+    struct msghdr msg;
+    struct canfd_frame frame;
+    int nbytes, i, maxdlen;
+    (void)maxdlen;
+    struct ifreq ifr;
+    struct timeval tv, last_tv;
+    (void)tv;
+    (void)last_tv;
+    struct timeval timeout_config = { 0, 0 }, *timeout_current = 0;
+
+    
+    for(i=0;i<currmax;i++)
+    {
+        s[i] = socket(PF_CAN, SOCK_RAW, CAN_RAW);
+        if (s[i] < 0) {
+            emit SIG_CANOPENSTATE(false,-1,"Create Socket Error");
+            return;
+        }
+
+        addr.can_family = AF_CAN;
+
+        memset(&ifr.ifr_name, 0, sizeof(ifr.ifr_name));
+        strncpy(ifr.ifr_name, CANNAME[i].data(), 5);
+
+        if (ioctl(s[i], SIOCGIFINDEX, &ifr) < 0) {
+            emit SIG_CANOPENSTATE(false,-2,"SIOCGIFINDEX");
+            return;
+        }
+        addr.can_ifindex = ifr.ifr_ifindex;
+
+        //CANFD Support
+        setsockopt(s[i], SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &canfd_on, sizeof(canfd_on));
+
+        if (bind(s[i], (struct sockaddr *)&addr, sizeof(addr)) < 0) {
+            emit SIG_CANOPENSTATE(false,-3,"bind error");
+            return;
+        }
+    }
+
+    mbCANOpen = true;
+    emit SIG_CANOPENSTATE(true,0,"open can card successfully");
+
+    iov.iov_base = &frame;
+    msg.msg_name = &addr;
+    msg.msg_iov = &iov;
+    msg.msg_iovlen = 1;
+    msg.msg_control = &ctrlmsg;
+
+    qint64 nLastRecv = QDateTime::currentMSecsSinceEpoch();
+    int nRecvState = 0; // 0 Have Data  1 No Data;
+
+    mbRunning = true;
+
+    int nrecvcount = 0;
+
+    while((!QThread::isInterruptionRequested())&&(mbCANOpen))
+    {
+        FD_ZERO(&rdfs);
+        for (i=0; i<currmax; i++)
+            FD_SET(s[i], &rdfs);
+
+        if (timeout_current)
+            *timeout_current = timeout_config;
+
+        timeout_config.tv_sec= 0;
+        timeout_config.tv_usec = 100;;
+        timeout_current = &timeout_config;
+        ret = select(s[currmax-1]+1, &rdfs, NULL, NULL, timeout_current);
+        if (ret < 0) {
+            emit SIG_CANOPENSTATE(false,-4,"select error");
+            mbCANOpen = false;
+            continue;
+        }
+
+        for (i=0; i<currmax; i++) {  /* check all CAN RAW sockets */
+
+            if (FD_ISSET(s[i], &rdfs)) {
+
+                nLastRecv = QDateTime::currentMSecsSinceEpoch();
+                /* these settings may be modified by recvmsg() */
+                iov.iov_len = sizeof(frame);
+                msg.msg_namelen = sizeof(addr);
+                msg.msg_controllen = sizeof(ctrlmsg);
+                msg.msg_flags = 0;
+
+                nbytes = recvmsg(s[i], &msg, 0);
+
+                if (nbytes < 0) {
+ //                   if ((errno == ENETDOWN) && !down_causes_exit) {
+                    if ((errno == ENETDOWN)) {
+                        emit SIG_CANOPENSTATE(false,-5,"can card down");
+                        fprintf(stderr, "%s: interface down\n", CANNAME[i].data());
+                        return;
+                    }
+                    continue;
+//                    perror("read");
+//                    return 1;
+                }
+
+                if ((size_t)nbytes == CAN_MTU)
+                    maxdlen = CAN_MAX_DLEN;
+                else if ((size_t)nbytes == CANFD_MTU)
+                    maxdlen = CANFD_MAX_DLEN;
+                else {
+                    continue;
+                }
+
+                nrecvcount++;
+  //              qDebug("receive msg.");
+                mMutex.lock();
+
+                basecan_msg msg;
+                msg.id = frame.can_id&0x1fffffff;
+                if((frame.can_id&0x80000000)!= 0)msg.isExtern = true;
+                else msg.isExtern = false;
+                if((frame.can_id&0x40000000)!= 0)msg.isRemote = true;
+                else msg.isRemote = false;
+                msg.nLen = frame.len;
+//                if(msg.id == 0x1c2)qDebug("id = %08x",msg.id);
+                if((frame.len<=64)&&(frame.len>0))memcpy(msg.data,frame.data,frame.len);
+                if(mMsgRecvBuf[i].size()<BUF_SIZE)
+                {
+                    mMsgRecvBuf[i].push_back(msg);
+                }
+
+                mMutex.unlock();
+
+            }
+        }
+
+        if((QDateTime::currentMSecsSinceEpoch() - nLastRecv)> 1000)
+        {
+            if(nRecvState == 0)
+            {
+                nRecvState = -1;
+            }
+        }
+        else
+        {
+            if(nRecvState == -1)
+            {
+                nRecvState = 0;
+            }
+        }
+
+        struct canfd_frame framesend[2500];
+
+
+        for(int nch =0;nch<currmax;nch++)
+        {
+            int nsend = 0;
+            mMutex.lock();
+            for(i=0;i<static_cast<int>( mMsgSendBuf[nch].size());i++)
+            {
+                if(i>=2500)break;
+                framesend[i].len = mMsgSendBuf[nch].at(i).nLen;
+                memcpy(framesend[i].data,mMsgSendBuf[nch].at(i).data,framesend[i].len);
+                framesend[i].can_id = mMsgSendBuf[nch].at(i).id;
+                if(mMsgSendBuf[nch].at(i).isExtern)
+                {
+                    framesend[i].can_id = framesend[i].can_id|0x80000000;
+                }
+                else
+                {
+                    framesend[i].can_id = framesend[i].can_id&0x7ff;
+                }
+                if(mMsgSendBuf[nch].at(i).isRemote)
+                {
+                    framesend[i].can_id= framesend[i].can_id|0x40000000;
+                }
+
+
+
+                nsend++;
+            }
+            mMsgSendBuf[nch].clear();
+            mMutex.unlock();
+            if(nsend > 0)
+            {
+                for(i=0;i<nsend;i++)
+                {
+                    int nsendbyte = 16;
+                    if(framesend[i].len>8)
+                    {
+                        nsendbyte = CANFD_MTU;
+                    }
+                if (write(s[nch], &framesend[i],nsendbyte) != nsendbyte) {
+                    perror("write error 1.");
+                    continue;
+                }
+                }
+            }
+
+        }
+
+    }
+
+    for (i=0; i<currmax; i++)
+    {
+        close(s[i]);
+    }
+    qDebug("nvcan thread close.");
+    mbRunning = false;
+}
+
+void nvcan::startdev()
+{
+    start();
+}
+
+void nvcan::stopdev()
+{
+    requestInterruption();
+
+    int64_t nstart = std::chrono::system_clock::now().time_since_epoch().count()/1000000;
+    int64_t nnow = std::chrono::system_clock::now().time_since_epoch().count()/1000000;
+    while(abs(nnow - nstart)<100)
+    {
+        nnow = std::chrono::system_clock::now().time_since_epoch().count()/1000000;
+        if(mbRunning == false)
+        {
+            qDebug("can is closed.");
+            break;
+        }
+    }
+}
+
+int nvcan::GetMessage(const int nch,basecan_msg *pMsg, const int nCap)
+{
+    if((nch>1)||(nch < 0))return -1;
+    if(mMsgRecvBuf[nch].size() == 0)return 0;
+
+    int nRtn;
+    nRtn = nCap;
+    mMutex.lock();
+    if(nRtn > static_cast<int>( mMsgRecvBuf[nch].size()))nRtn = mMsgRecvBuf[nch].size();
+    int i;
+    for(i=0;i<nRtn;i++)
+    {
+        memcpy(&pMsg[i],&(mMsgRecvBuf[nch].at(i)),sizeof(basecan_msg));
+    }
+
+    std::vector<basecan_msg>::iterator iter;
+    iter = mMsgRecvBuf[nch].begin();
+    for(i=0;i<nRtn;i++)
+    {
+        iter = mMsgRecvBuf[nch].erase(iter);
+    }
+
+    mMutex.unlock();
+
+    return nRtn;
+
+}
+
+int nvcan::SetMessage(const int nch, basecan_msg *pMsg)
+{
+    if((nch>1)||(nch < 0))return -1;
+
+    if(mMsgSendBuf[nch].size() > BUF_SIZE)return -2;
+
+    mMutex.lock();
+    mMsgSendBuf[nch].push_back(*pMsg);
+    mMutex.unlock();
+    return 0;
+}
+
+void nvcan::onMsg(bool bCAN, int nR, const char *strres)
+{
+    (void)bCAN;
+    (void)nR;
+    std::cout<<"msg is: "<<strres<<std::endl;
+}
+

+ 0 - 1
src/tool/IVSysMan/main.cpp

@@ -17,7 +17,6 @@ iv::Ivfault * ivfault;
 
 #define USE_ONEIVSYSMAN
 
-
 extern bool gbOneThreadRunning ;
 extern bool gbOneThreadRun ;
 void threadOne(QSharedMemory * pshare,int ncount)

+ 84 - 24
src/tool/adciv_maketool/mainwindow.cpp

@@ -4,6 +4,7 @@
 #include <QFile>
 #include <iostream>
 #include <QFileDialog>
+#include <QMessageBox>
 
 MainWindow::MainWindow(QWidget *parent)
     : QMainWindow(parent)
@@ -22,6 +23,11 @@ MainWindow::MainWindow(QWidget *parent)
     connect(&mProc,SIGNAL(readyReadStandardOutput()),this,SLOT(onReadStandardOutput()));
     connect(&mProc,SIGNAL(readyReadStandardError()),this,SLOT(onReadStandardError()));
     connect(&mProc,SIGNAL(finished(int)),this,SLOT(onfinish()));
+
+    connect(&mProcBuild,SIGNAL(readyReadStandardOutput()),this,SLOT(onBuildReadStandardOutput()));
+    connect(&mProcBuild,SIGNAL(readyReadStandardError()),this,SLOT(onBuildReadStandardError()));
+    connect(&mProcBuild,SIGNAL(finished(int)),this,SLOT(onBuildfinish(int)));
+
     Checkqmakesh();
     Checkdeploysh();
 }
@@ -56,6 +62,64 @@ void MainWindow::onReadStandardError()
  //   qDebug("error: %s",str.toLatin1().data());
 }
 
+void MainWindow::onfinish()
+{
+    ui->pushButton_findqmake->setEnabled(true);
+    //    qDebug("outputs:\n  %s",mstrfindqmake.toLatin1().data());
+
+    QByteArray ba = QByteArray(mstrfindqmake.toLatin1().data());
+    QList<QByteArray> balist =  ba.split('\n');
+    //    qDebug("ba len %d",balist.size());
+
+    int nsize = static_cast<int>(balist.size());
+    int i;
+    for(i=0;i<nsize;i++)
+    {
+        QString strline = QString(balist[i]);
+        if(strline.indexOf("---qmake---:")>=0)
+        {
+            std::cout<<" find qmake."<<std::endl;
+            QString strqmake = strline.mid(12);
+            std::cout<<" qmake path: "<<strqmake.toLatin1().data()<<std::endl;
+            ui->lineEdit_qmakepath->setText(strqmake);
+            break;
+        }
+    }
+}
+
+void MainWindow::onBuildReadStandardOutput()
+{
+    QProcess * proc = (QProcess *)sender();
+    QByteArray ba = proc->readAllStandardOutput();
+  ///  qDebug("out:");
+
+    ui->plainTextEdit_output->appendPlainText(QString(ba.toStdString().data()));
+
+ //   qDebug("%s",ba.toStdString().data());
+}
+
+void MainWindow::onBuildReadStandardError()
+{
+    QProcess * proc = (QProcess *)sender();
+    QByteArray ba = proc->readAllStandardError();
+    ui->plainTextEdit_error->appendPlainText(QString(ba.toStdString().data()));
+    //   QString str = QString(ba);
+    //   qDebug("error: %s",str.toLatin1().data());
+}
+
+void MainWindow::onBuildfinish(int nrtn)
+{
+    QDir xDir;
+    xDir.remove(mstrcurbuildsh);
+    ui->pushButton_SelectPro->setEnabled(true);
+
+    if(nrtn > 0)
+    {
+        QMessageBox::warning(this,tr("Warning"),tr("Build Fail. Please Check."),QMessageBox::YesAll);
+    }
+    qDebug("nrtn : %d",nrtn);
+}
+
 void MainWindow::Checkqmakesh()
 {
     QFile xFile;
@@ -156,35 +220,15 @@ void MainWindow::Checkdeploysh()
     }
 }
 
-void MainWindow::onfinish()
-{
-    ui->pushButton_findqmake->setEnabled(true);
-//    qDebug("outputs:\n  %s",mstrfindqmake.toLatin1().data());
-
-    QByteArray ba = QByteArray(mstrfindqmake.toLatin1().data());
-    QList<QByteArray> balist =  ba.split('\n');
-//    qDebug("ba len %d",balist.size());
 
-    int nsize = static_cast<int>(balist.size());
-    int i;
-    for(i=0;i<nsize;i++)
-    {
-        QString strline = QString(balist[i]);
-        if(strline.indexOf("---qmake---:")>=0)
-        {
-            std::cout<<" find qmake."<<std::endl;
-            QString strqmake = strline.mid(12);
-            std::cout<<" qmake path: "<<strqmake.toLatin1().data()<<std::endl;
-            ui->lineEdit_qmakepath->setText(strqmake);
-            break;
-        }
-    }
-}
 
 
 
 void MainWindow::on_pushButton_SelectPro_clicked()
 {
+    ui->plainTextEdit_output->clear();
+    ui->plainTextEdit_error->clear();
+
     QString str = QFileDialog::getOpenFileName(this,tr("Please Select .pro file"),".","*.pro");
 
     if(str.isEmpty())return;
@@ -194,14 +238,28 @@ void MainWindow::on_pushButton_SelectPro_clicked()
 
 
     BuildProgram(str);
+
+
 }
 
 void MainWindow::BuildProgram(QString & strpropath)
 {
-    MakeBuildSH(strpropath);
     //make build sh
+    QString strshpath = MakeBuildSH(strpropath);
 
+    if(strshpath.length()<1)
+    {
+        QMessageBox::warning(this,tr("Warning"),tr("Make  Build Shell Fail."),QMessageBox::YesAll);
+        ui->pushButton_SelectPro->setEnabled(true);
+    }
+
+    mstrcurbuildsh = strshpath;
     //build
+
+    QStringList arg;
+    arg.append(strshpath);
+    marg_procbuild = arg;
+    mProcBuild.start("/bin/bash",marg_procbuild);
 }
 
 QString MainWindow::MakeBuildSH(QString & strpropath)
@@ -290,6 +348,8 @@ QString MainWindow::MakeBuildSH(QString & strpropath)
 
     delete[] strshinfo;
 
+    return strshpath;
+
 
 
 }

+ 10 - 0
src/tool/adciv_maketool/mainwindow.h

@@ -3,6 +3,7 @@
 
 #include <QMainWindow>
 #include <QProcess>
+#include <QDir>
 
 #include "threadfindqmake.h"
 
@@ -23,6 +24,10 @@ private slots:
     void onReadStandardError();
     void onfinish();
 
+    void onBuildReadStandardOutput();
+    void onBuildReadStandardError();
+    void onBuildfinish(int nrtn);
+
 private slots:
     void on_pushButton_findqmake_clicked();
 
@@ -34,9 +39,14 @@ private:
     QProcess mProc;
     QStringList marg_proc;
 
+    QProcess mProcBuild;
+    QStringList marg_procbuild;
+
     QString mstrqmakepath;
     QString mstrfindqmake;
 
+    QString mstrcurbuildsh;
+
 private:
     void Checkqmakesh();
     void Checkdeploysh();

+ 51 - 5
src/tool/adciv_maketool/mainwindow.ui

@@ -6,8 +6,8 @@
    <rect>
     <x>0</x>
     <y>0</y>
-    <width>800</width>
-    <height>600</height>
+    <width>810</width>
+    <height>631</height>
    </rect>
   </property>
   <property name="windowTitle">
@@ -53,8 +53,8 @@
    <widget class="QPushButton" name="pushButton_SelectPro">
     <property name="geometry">
      <rect>
-      <x>160</x>
-      <y>170</y>
+      <x>280</x>
+      <y>110</y>
       <width>141</width>
       <height>41</height>
      </rect>
@@ -63,13 +63,59 @@
      <string>Select pro</string>
     </property>
    </widget>
+   <widget class="QPlainTextEdit" name="plainTextEdit_output">
+    <property name="geometry">
+     <rect>
+      <x>10</x>
+      <y>200</y>
+      <width>771</width>
+      <height>161</height>
+     </rect>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_2">
+    <property name="geometry">
+     <rect>
+      <x>10</x>
+      <y>170</y>
+      <width>241</width>
+      <height>21</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>Build Output:</string>
+    </property>
+   </widget>
+   <widget class="QPlainTextEdit" name="plainTextEdit_error">
+    <property name="geometry">
+     <rect>
+      <x>12</x>
+      <y>417</y>
+      <width>771</width>
+      <height>161</height>
+     </rect>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_3">
+    <property name="geometry">
+     <rect>
+      <x>10</x>
+      <y>385</y>
+      <width>271</width>
+      <height>21</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>Build Warning or Error:</string>
+    </property>
+   </widget>
   </widget>
   <widget class="QMenuBar" name="menubar">
    <property name="geometry">
     <rect>
      <x>0</x>
      <y>0</y>
-     <width>800</width>
+     <width>810</width>
      <height>27</height>
     </rect>
    </property>

+ 2 - 0
src/tool/adciv_maketool/maketool_deploy.sh

@@ -129,4 +129,6 @@ for fileName in $xlib
 
 rm -rf app
 
+rm $EXE
+
 

+ 13 - 3
src/tool/adciv_maketool/maketool_deploylib.sh

@@ -9,7 +9,7 @@ QtLibDir=/usr/lib/aarch64-linux-gnu/
 else
 Qtgccdir='/usr/lib/x86_64-linux-gnu/qt5'
 QtPlatformdir=$Qtgccdir/plugins/platforms
-QtLibDir=/usr/lib/x86_64-linux-gnu
+QtLibDir=/usr/lib/x86_64-linux-gnu/
 fi
 
 
@@ -93,7 +93,7 @@ files=`ldd $EXE | awk '{ if(match($3,"^/"))printf("%s "),$3 }'`
 cp $files $PWD/app/lib
 cp $PWD/commonlib/lib/* $PWD/app/lib
 cp -r  $PWD/commonlib/platforms $PWD/app
-cp $EXE $PWD/app
+cp $EXE $PWD/app/lib
 
 for x in ${ignore_lib_name[@]}
 do
@@ -103,20 +103,30 @@ done
 rm -rf commonlib
 
 cd app
-patchelf --set-rpath '$ORIGIN/lib/' $EXE
+cd lib
+patchelf --set-rpath '$ORIGIN' $EXE
 if [ "$?" != 0 ];then
 	echo -e "\e[31m deploy.sh: patchelf $EXE faile, Ensure patchelf tool installed\e[0m"
 	exit 1
 fi
+cd ..
 cd platforms
 patchelf --set-rpath '$ORIGIN/../lib/' libqxcb.so
 if [ "$?" != 0 ];then
 	echo -e "\e[31m deploy.sh: patchelf $EXE faile, Ensure patchelf tool installed\e[0m"
 #	exit 1
 fi
+
+echo "current dir"
+echo `pwd`
+
 cd ..
 cd ..
 
+
+echo "current dir"
+echo `pwd`
+
 cp -r app $PWD/deploy/
 
 xlib=`ls ./deploy/app/lib/lib*`  

+ 1 - 0
src/tool/adciv_maketool/threadfindqmake.cpp

@@ -17,6 +17,7 @@ void ThreadFindQMake::threadqmake()
     {
         std::cout<<" open file success."<<std::endl;
         QByteArray ba = xFile.readAll();
+        (void)ba;
         QProcess * pProcess = new QProcess();
         QStringList arg;
         arg.append("/home/yuchuli/test.sh");