Browse Source

Merge http://192.168.14.36:3000/adc_pilot/modularization

孙嘉城 3 years ago
parent
commit
62c6b899dd
97 changed files with 8222 additions and 89 deletions
  1. 14 4
      autodeploy.sh
  2. 11 0
      build_partial.sh
  3. 341 0
      sh/BaiDuMap.html
  4. BIN
      sh/car.png
  5. 11 6
      src/controller/controller_yuhesen/control/control_status.cpp
  6. 5 5
      src/controller/controller_yuhesen/main.cpp
  7. 4 1
      src/decition/decition_brain/decition/adc_adapter/yuhesen_adapter.cpp
  8. 3 3
      src/decition/decition_brain/decition/brain.cpp
  9. 4 0
      src/decition/decition_brain/decition/decide_gps_00.cpp
  10. 1 0
      src/decition/decition_brain/decition/decide_gps_00.h
  11. 1 1
      src/decition/decition_brain_sf/decition/brain.cpp
  12. 5 0
      src/decition/decition_brain_sf/decition/decide_gps_00.cpp
  13. 2 0
      src/decition/decition_brain_sf/decition/decide_gps_00.h
  14. 108 0
      src/tool/map_lanetoxodr/adcxodrviewer.pro
  15. 128 0
      src/tool/map_lanetoxodr/adcxodrviewer_android.pro
  16. 91 0
      src/tool/map_lanetoxodr/android/AndroidManifest.xml
  17. BIN
      src/tool/map_lanetoxodr/android/libs/android-support-v4.jar
  18. 1 0
      src/tool/map_lanetoxodr/android/libs/android-support-v4.jar.properties
  19. 12 0
      src/tool/map_lanetoxodr/android/src/an/qt/extendsQtWithJava/ExtendsQtNative.java
  20. 348 0
      src/tool/map_lanetoxodr/android/src/an/qt/extendsQtWithJava/ExtendsQtWithJava.java
  21. 136 0
      src/tool/map_lanetoxodr/filedialogextern.cpp
  22. 56 0
      src/tool/map_lanetoxodr/filedialogextern.h
  23. 58 2
      src/tool/map_lanetoxodr/main.cpp
  24. 98 2
      src/tool/map_lanetoxodr/mainwindow.cpp
  25. 15 0
      src/tool/map_lanetoxodr/mainwindow.h
  26. 6 3
      src/tool/map_lanetoxodr/map_lanetoxodr.pro
  27. 75 0
      src/tool/map_lanetoxodr/myview.cpp
  28. 11 0
      src/tool/map_lanetoxodr/myview.h
  29. 265 0
      src/tool/map_lanetoxodr/roaddigit.cpp
  30. 56 0
      src/tool/map_lanetoxodr/roaddigit.h
  31. 50 5
      src/tool/map_lanetoxodr/roadeditdialog.cpp
  32. 8 0
      src/tool/map_lanetoxodr/roadeditdialog.h
  33. 2 0
      src/tool/map_lanetoxodr/roadviewitem.cpp
  34. 2 2
      src/tool/map_lanetoxodr/roadviewitem.h
  35. 65 0
      src/tool/map_lanetoxodr/simpleCustomEvent.cpp
  36. 31 0
      src/tool/map_lanetoxodr/simpleCustomEvent.h
  37. 9 1
      src/tool/map_lanetoxodr/xodrfunc.cpp
  38. 226 0
      src/tool/map_lanetoxodr/xodrscenfunc.cpp
  39. 26 0
      src/tool/map_lanetoxodr/xodrscenfunc.h
  40. 315 0
      src/tool/map_lanetoxodr/xvmainwindow.cpp
  41. 81 0
      src/tool/map_lanetoxodr/xvmainwindow.h
  42. 79 0
      src/tool/map_lanetoxodr/xvmainwindow.ui
  43. 134 50
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp
  44. 20 0
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.h
  45. 49 1
      src/ui/ui_ads_hmi/ADCIntelligentVehicle.ui
  46. 341 0
      src/ui/ui_ads_hmi/BaiDuMap.html
  47. 7 3
      src/ui/ui_ads_hmi/ui_ads_hmi.pro
  48. 73 0
      src1/common/modulecomm/.gitignore
  49. 152 0
      src1/common/modulecomm/modulecomm.cpp
  50. 64 0
      src1/common/modulecomm/modulecomm.h
  51. 36 0
      src1/common/modulecomm/modulecomm.pro
  52. 323 0
      src1/common/modulecomm_fastrtps/Topics.cxx
  53. 253 0
      src1/common/modulecomm_fastrtps/Topics.h
  54. 13 0
      src1/common/modulecomm_fastrtps/Topics.idl
  55. 138 0
      src1/common/modulecomm_fastrtps/TopicsPubSubTypes.cxx
  56. 61 0
      src1/common/modulecomm_fastrtps/TopicsPubSubTypes.h
  57. 198 0
      src1/common/modulecomm_fastrtps/TopicsPublisher.cxx
  58. 56 0
      src1/common/modulecomm_fastrtps/TopicsPublisher.h
  59. 206 0
      src1/common/modulecomm_fastrtps/TopicsSubscriber.cxx
  60. 72 0
      src1/common/modulecomm_fastrtps/TopicsSubscriber.h
  61. 13 0
      src1/common/modulecomm_fastrtps/ivmodulemsg_type.h
  62. 63 0
      src1/common/modulecomm_fastrtps/modulecomm_fastrtps.cpp
  63. 40 0
      src1/common/modulecomm_fastrtps/modulecomm_fastrtps.h
  64. 45 0
      src1/common/modulecomm_fastrtps/modulecomm_fastrtps.pro
  65. 140 0
      src1/common/modulecomm_fastrtps/modulecomm_impl.cpp
  66. 41 0
      src1/common/modulecomm_fastrtps/modulecomm_impl.h
  67. 73 0
      src1/common/modulecomm_inter/.gitignore
  68. 480 0
      src1/common/modulecomm_inter/intercomm.cpp
  69. 109 0
      src1/common/modulecomm_inter/intercomm.h
  70. 56 0
      src1/common/modulecomm_inter/modulecomm_inter.cpp
  71. 37 0
      src1/common/modulecomm_inter/modulecomm_inter.h
  72. 33 0
      src1/common/modulecomm_inter/modulecomm_inter.pro
  73. 90 0
      src1/common/modulecomm_shm/ReadMe.md
  74. 13 0
      src1/common/modulecomm_shm/ivmodulemsg_type.h
  75. 54 0
      src1/common/modulecomm_shm/modulecomm_shm.cpp
  76. 42 0
      src1/common/modulecomm_shm/modulecomm_shm.h
  77. 41 0
      src1/common/modulecomm_shm/modulecomm_shm.pro
  78. 378 0
      src1/common/modulecomm_shm/procsm.cpp
  79. 112 0
      src1/common/modulecomm_shm/procsm.h
  80. 310 0
      src1/common/modulecomm_shm/procsm_if.cpp
  81. 99 0
      src1/common/modulecomm_shm/procsm_if.h
  82. 73 0
      src1/driver/driver_lidar_rs16/.gitignore
  83. 61 0
      src1/driver/driver_lidar_rs16/driver_lidar_rs16.pro
  84. 139 0
      src1/driver/driver_lidar_rs16/ivdriver_lidar_rs16.cpp
  85. 20 0
      src1/driver/driver_lidar_rs16/ivdriver_lidar_rs16.h
  86. 19 0
      src1/driver/driver_lidar_rs16/main.cpp
  87. 10 0
      src1/driver/interface/ivdriver.cpp
  88. 16 0
      src1/driver/interface/ivdriver.h
  89. 141 0
      src1/driver/interface/ivdriver_lidar.cpp
  90. 64 0
      src1/driver/interface/ivdriver_lidar.h
  91. 220 0
      src1/driver/interface/lidarmain.cpp
  92. 8 0
      src1/driver/interface/lidarmain.h
  93. 45 0
      src1/interface/ivmodule.cpp
  94. 31 0
      src1/interface/ivmodule.h
  95. 73 0
      src1/test/testmodulecomm_inter/.gitignore
  96. 42 0
      src1/test/testmodulecomm_inter/main.cpp
  97. 35 0
      src1/test/testmodulecomm_inter/testmodulecomm_inter.pro

+ 14 - 4
autodeploy.sh

@@ -69,13 +69,23 @@ do
 	fi
 done
 
-echo "creat IVSysMan.xml"
-cp ./other/$CONFIG_IVSysMan ./deploy/app/IVSysMan.xml
-cp ./other/ADS_decision.xml ./deploy/app/ADS_decision.xml
-sed -i "s|xxxxxx|$PRO_DIR/deploy/app|g" ./deploy/app/IVSysMan.xml
+#echo "creat IVSysMan.xml"
+#cp ./other/$CONFIG_IVSysMan ./deploy/app/IVSysMan.xml
+#cp ./other/ADS_decision.xml ./deploy/app/ADS_decision.xml
+#sed -i "s|xxxxxx|$PRO_DIR/deploy/app|g" ./deploy/app/IVSysMan.xml
 
 cp ./bin/*.so ./deploy/app/lib/
 
+qt_com=`arch`
+if [ $qt_com = "aarch64" ];then
+cp -r /usr/lib/aarch64-linux-gnu/nss/* ./deploy/app/lib/
+else
+cp -r /usr/lib/x86_64-linux-gnu/nss/* ./deploy/app/lib/
+fi
+
+cp ./sh/BaiDuMap.html ./deploy/app/
+cp ./sh/car.png ./deploy/app/
+
 echo ""
 echo "***************"
 echo "***  done!  ***"

+ 11 - 0
build_partial.sh

@@ -68,3 +68,14 @@ else
 	echo -e "\e[31m Can't find module code, exit.....\e[0m"
 	exit
 fi
+
+
+qt_com=`arch`
+if [ $qt_com = "aarch64" ];then
+cp -r /usr/lib/aarch64-linux-gnu/nss/* ./deploy/app/lib/
+else
+cp -r /usr/lib/x86_64-linux-gnu/nss/* ./deploy/app/lib/
+fi
+
+cp ./sh/BaiDuMap.html ./deploy/app/
+cp ./sh/car.png ./deploy/app/

+ 341 - 0
sh/BaiDuMap.html

@@ -0,0 +1,341 @@
+
+
+<!DOCTYPE html>
+<html>
+<head>
+    <meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
+    <meta name="viewport" content="initial-scale=1.0, user-scalable=no" />
+    <style type="text/css">
+        body, html, #allmap {
+            width: 100%;
+            height: 100%;
+            overflow: hidden;
+            margin: 0;
+            font-family: "微软雅黑";
+        }
+    </style>
+    <script type="text/javascript" src="http://api.map.baidu.com/api?v=2.0&ak=EVi8PXiYpKBGvBr7tgGMzcbdwzWWNf2o"></script>
+
+    
+    <title>野火GPS地图</title>
+</head>
+<body>
+    <div id="allmap"></div>
+
+
+
+</body>
+</html>
+
+
+
+<script type="text/javascript">
+    try {
+
+   
+    // 百度地图API功能
+    var map = new BMap.Map("allmap");            // 创建Map实例
+
+    //添加拖拽和缩放功能
+    map.enableScrollWheelZoom(true);
+    map.enableDragging();   
+
+    //添加控件和比例尺
+    var top_right_control = new BMap.ScaleControl({ anchor: BMAP_ANCHOR_BOTTOM_LEFT });// 左下角,添加比例尺
+    var top_right_navigation = new BMap.NavigationControl({ anchor: BMAP_ANCHOR_BOTTOM_LEFT });  //左下角,添加默认缩放平移控件
+
+    map.addControl(top_right_control);
+    map.addControl(top_right_navigation);
+
+
+    //添加地图类型
+    var mapType1 = new BMap.MapTypeControl({ mapTypes: [BMAP_NORMAL_MAP, BMAP_HYBRID_MAP] });
+    var mapType2 = new BMap.MapTypeControl({ anchor: BMAP_ANCHOR_TOP_LEFT });
+
+    //添加地图类型和缩略图
+   
+    map.addControl(mapType1);          //2D图,卫星图
+    map.addControl(mapType2);          //左上角,默认地图控件
+
+    var drawtrail = 0;
+
+    var grotation = 0;
+
+
+    //创建点
+    //map.clearOverlays();
+    var point = new BMap.Point(117.355, 39.066);
+    var markerCur = new BMap.Marker(point);
+    var markerObj = new BMap.Marker(point);
+    var havepointlast = 0;
+    var pointlast = new BMap.Point(116,39);
+    var pointobj = new BMap.Point(116,39);
+    var bobjset = 0;
+    var gtracelist = []; 
+    var gtraceraw = [];
+    var tracenow = 0;
+    var tracenum = 0;
+    map.centerAndZoom(point, 18);
+    var convertor = new BMap.Convertor();
+    var polylineTrace;
+/*
+    var polylineTrace =new BMap.Polyline(gtracelist, {
+    enableEditing: false,//是否启用线编辑,默认为false
+    enableClicking: false,//是否响应点击事件,默认为true
+    strokeWeight:'4',//折线的宽度,以像素为单位
+    strokeOpacity: 0.8,//折线的透明度,取值范围0 - 1
+    strokeColor:"red" //折线颜色
+    });*/
+    //var marker = new BMap.Marker(point);  // 创建标注
+    //map.addOverlay(marker);               // 将标注添加到地图中
+    
+    //根据IP定位城市
+    function myFun(result) {
+        var cityName = result.name;
+        map.setCenter(cityName);
+    }
+    var myCity = new BMap.LocalCity();
+    myCity.get(myFun);
+
+	var icon = new BMap.Icon('car.png',new BMap.Size(15,30));
+        icon.imageSize = new BMap.Size(15,30);
+        icon.anchor = new BMap.Size(8,15);
+        
+
+    //showalert(testmsg);
+
+    //对传入的经纬度进行标注:纬度,经度
+   // var Latt = 116.404;
+   // var Lott = 39.915;
+
+   // theLocation(Latt, Lott);
+   // testAlert();
+
+    function SetDrawTrail(x)
+   {
+	
+	if(x == 1)drawtrail = 1;
+	else drawtrail = 0;
+   }    
+
+
+    function clear()
+    {
+	gtracelist = [];
+    }
+
+   
+        // 用经纬度设置地图中心点
+    function objLocation(Longitude,Latitude) {
+
+        var gpsPoint = new BMap.Point(Longitude, Latitude);
+
+	var pointArr = [];
+	pointArr.push(gpsPoint);
+        convertor.translate(pointArr, 1, 5, translateCallbackobj)
+        //gps坐标纠偏
+ //       BMap.Convertor.translate(gpsPoint, 0, translateCallbackobj);     //真实经纬度转成百度坐标
+
+
+    }
+
+    // 用经纬度设置地图中心点
+    function theLocation(Longitude,Latitude,rotation) {
+        
+        grotation = rotation;
+        var gpsPoint = new BMap.Point(Longitude, Latitude);
+
+        //gps坐标纠偏
+
+
+var pointArr = [];
+pointArr.push(gpsPoint);
+        convertor.translate(pointArr, 1, 5, translateCallback)
+//convertor.translate(gpsPoint, 0, translateCallback);     //真实经纬度转成百度坐标
+ //       BMap.Convertor.translate(gpsPoint, 0, translateCallback);     //真实经纬度转成百度坐标
+
+
+            //map.clearOverlays();
+            //var new_point = new BMap.Point(Longitude,Latitude );
+            //var marker = new BMap.Marker(new_point);  // 创建标注
+            //map.addOverlay(marker);              // 将标注添加到地图中
+            //map.panTo(new_point);
+            //marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+
+    }
+
+
+function settrace(numlist,num2list)                    //仅把qt传来的数组转换成可用的list
+{
+    //alert(numlist);
+    var num_list,num2_list;                         //以下为格式转换,分割成可用的数组
+    num_list = numlist.substring(1,numlist.length-1);
+    num2_list = num2list.substring(1,num2list.length-1);
+    num_list = num_list.split(",");
+    num2_list = num2_list.split(",");
+    //alert("the num_list is: "+num_list[0]+" "+num_list[1]);
+
+    
+    gtraceraw = [];
+    gtracelist = [];
+    for(i=0;i<num_list.length;i++)
+    {
+        point= new BMap.Point(num_list[i],num2_list[i]);
+        gtraceraw.push(point);                                  
+    }
+    tracenum = num_list.length;
+    tracenow = 0;
+
+    setTimeout("converttrace()", 30);// 调用画轨迹的函数
+
+    
+}
+
+function converttrace() 
+{
+    var tracelist = [];     //为轨迹做准备,把所有的点扔里面,但不对每个点标注
+    var index = 0;
+    for(i=tracenow;i<tracenum;i++)
+    {
+	tracelist.push(gtraceraw[i]);
+	index++;
+	if(index>=10)break;
+    }
+    if(index>0)
+    {
+	
+        convertor.translate(tracelist, 1,5,translateCallbacktrace);     //真实经纬度转成百度坐标
+     }
+
+}
+
+
+translateCallbacktrace = function (data){
+      if(data.status == 0) {
+        for (var i = 0; i < data.points.length; i++) {
+	gtracelist.push(data.points[i]);
+        }
+	tracenow = tracenow + data.points.length;
+      }
+
+    map.removeOverlay(polylineTrace);
+    polylineTrace =new BMap.Polyline(gtracelist, {
+    enableEditing: false,//是否启用线编辑,默认为false
+    enableClicking: false,//是否响应点击事件,默认为true
+    strokeWeight:'4',//折线的宽度,以像素为单位
+    strokeOpacity: 0.8,//折线的透明度,取值范围0 - 1
+    strokeColor:"red" //折线颜色
+    });
+    map.addOverlay(polylineTrace);          //增加折线
+      setTimeout("converttrace()", 250);// 调用画轨迹的函数
+	
+}
+
+
+
+
+    // 用经纬度设置地图中心点
+    function testAlert(msg) {
+
+        var str = new String;
+        str =  msg.toString()
+       // str = "test"
+
+        alert(str);
+    }
+
+    function enableZoomDrag()
+    {
+        //添加拖拽和缩放功能
+        map.enableScrollWheelZoom(true);
+        map.enableDragging();
+    }
+
+        //坐标转换完之后的回调函数
+    translateCallbackmap = function (point) {
+
+	gtracelist.push(point);       
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+        //坐标转换完之后的回调函数
+    translateCallbacktr = function (point) {
+
+	gtracelist.push(point);       
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+    //坐标转换完之后的回调函数
+    translateCallbackobj = function (data) {
+	if(data.status === 0) {
+         var point = data.points[0];
+	pointobj = point;
+	bobjset = 1;
+ //       map.clearOverlays();
+	map.removeOverlay(markerObj);
+        markerObj = new BMap.Marker(point);
+
+        map.addOverlay(markerObj);
+	}
+
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+
+    //坐标转换完之后的回调函数
+    translateCallback = function (data) {
+
+if(data.status === 0) {
+         var point = data.points[0]
+        map.removeOverlay(markerCur);
+        markerCur = new BMap.Marker(point);
+        if(havepointlast == 1)
+	{
+		if(drawtrail == 1)
+		{
+		var line = new BMap.Polyline([pointlast, point], {strokeColor: "green", strokeWeight: 1, strokeOpacity: 1});
+		map.addOverlay(line);  
+		line.disableMassClear();
+		}
+	}
+        pointlast = point;
+        havepointlast = 1;
+
+	markerCur.setOffset(-30,-30);
+	markerCur.setIcon(icon); 
+	markerCur.setShadow(icon) 
+	markerCur.setRotation(grotation);
+        map.addOverlay(markerCur);
+        map.setCenter(point);
+      }
+//	return;
+//        map.clearOverlays();
+
+/*
+	if(bobjset == 1)
+	{
+		map.removeOverlay(markerObj);
+        	markerObj = new BMap.Marker(pointobj);
+
+        	map.addOverlay(markerObj);
+	}
+
+*/
+
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+    } catch (e) {
+
+        alert("地图加载失败,请检查网络!");
+
+    }
+
+   
+</script>
+
+
+

BIN
sh/car.png


+ 11 - 6
src/controller/controller_yuhesen/control/control_status.cpp

@@ -1,5 +1,10 @@
 #include <control/control_status.h>
 
+
+#define GET_HIGH_BYTE(x)  ((x >> 8) & 0xFF) 
+#define GET_LOW_BYTE(x)   (x & 0xFF)
+
+
 void iv::control::ControlStatus::set_head()
 {
     command.bit.head = 0xEB;
@@ -8,20 +13,20 @@ void iv::control::ControlStatus::set_head()
 void iv::control::ControlStatus::set_wheel_angle(float angle)
 {
     int ang = (int)(angle * 100);
-    command.bit.ang_H = (ang) >> 8;
-    command.bit.ang_L = (ang) % 256;
+    command.bit.ang_H = get_HIGH_BYTE(ang);
+    command.bit.ang_L = get_LOW_BYTE(ang);
 }
 
 void iv::control::ControlStatus::set_brake(bool enable)
 {
-    command.bit.brake=(unsigned)enable;
+    command.bit.brake=(unsigned char)enable;
 }
 
 void iv::control::ControlStatus::set_velocity(float vel)
 {
     int v = (int)(vel * 1000);
-    command.bit.vel_H = v >> 8;
-    command.bit.vel_L = v % 256;
+    command.bit.vel_H = get_HIGH_BYTE(v);
+    command.bit.vel_L = get_LOW_BYTE(v);
 }
 
 void iv::control::ControlStatus::set_left_light(bool enable)
@@ -42,7 +47,7 @@ void iv::control::ControlStatus::set_right_light(bool enable)
 
 void iv::control::ControlStatus::set_highbeam(bool enable)
 {
-    command.bit.high_beam = (char)enable;
+    command.bit.high_beam = (unsigned char)enable;
 }
 
 void iv::control::ControlStatus::set_dangwei(int dangwei)

+ 5 - 5
src/controller/controller_yuhesen/main.cpp

@@ -58,7 +58,7 @@ void executeDecition(const iv::brain::decition decition)
     std::cout<<" brake is "<<decition.brake()<<std::endl;
     std::cout<<"drive_mode is "<<decition.mode()<<std::endl;
     std::cout<<" dangwei is "<<decition.gear()<<std::endl;
-    std::cout<<"dspeed is" << decition.speed()<<std::endl;
+    std::cout<<"dspeed is " << decition.speed()<<std::endl;
     gcontroller->inialize();
     gcontroller->control_wheel(decition.wheelangle());
     gcontroller->control_brake(decition.brake());
@@ -207,14 +207,14 @@ int main(int argc, char *argv[])
      QString strpath = QCoreApplication::applicationDirPath();
 
     if(argc < 2)
-        strpath = strpath + "/controller_midcar.xml";
+        strpath = strpath + "/controller_yuhesen.xml";
     else
         strpath = argv[1];
     std::cout<<strpath.toStdString()<<std::endl;
 
-    gdecition_def.set_brake(0);
-    gdecition_def.set_torque(0);
-    gdecition_def.set_speed(105);
+//    gdecition_def.set_brake(0);
+//    gdecition_def.set_torque(0);
+//    gdecition_def.set_speed(105);
     gTime.start();
 
     gcontroller = boost::shared_ptr<iv::control::Controller>(new iv::control::Controller());

+ 4 - 1
src/decition/decition_brain/decition/adc_adapter/yuhesen_adapter.cpp

@@ -89,12 +89,15 @@ std::cout<<"==========================================="<<std::endl;
      std::cout<<"dSpeed:"<<dSpeed<<"   realSpeed:"<<realSpeed<<"   acc:"<<accAim
     <<std::endl;
 std::cout<<"========================================="<<std::endl;
-(*decition)->speed=5/3.6;
+(*decition)->speed = dSpeed/3.6;
 (*decition)->wheel_angle=(*decition)->wheel_angle*0.1;
 (*decition)->wheel_angle=max((float)-40.0,(*decition)->wheel_angle);
 (*decition)->wheel_angle=min((float)40.0,(*decition)->wheel_angle);
 (*decition)->mode=1;
 (*decition)->dangWei=1;
+if((*decition)->brake>0){
+    (*decition)->speed=0;
+}
     return *decition;
 }
 

+ 3 - 3
src/decition/decition_brain/decition/brain.cpp

@@ -1,4 +1,4 @@
-#include <decition/brain.h>
+ #include <decition/brain.h>
 #include <fstream>
 #include <time.h>
 #include <exception>
@@ -403,7 +403,7 @@ void iv::decition::BrainDecition::run() {
         ServiceCarStatus.useObsPredict = true;
     }
 
-    std::string inRoadAvoid = xp.GetParam("inRoadAvoid","true");  //If Use MPC set true
+    std::string inRoadAvoid = xp.GetParam("inRoadAvoid","false");  //If Use MPC set true
     if(inRoadAvoid == "true")
     {
         ServiceCarStatus.inRoadAvoid = true;
@@ -1024,7 +1024,7 @@ void iv::decition::BrainDecition::UpdateMap(const char *mapdata, const int mapda
         }
 
         mmpcapi.SetMAP(xvectorMAP);
-
+                                                                                                    
         if(ServiceCarStatus.speed_control==true){
         Compute00().getDesiredSpeed(navigation_data);}
         mMutexMap.unlock();

+ 4 - 0
src/decition/decition_brain/decition/decide_gps_00.cpp

@@ -986,6 +986,10 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
          gpsMapLine[PathPoint]->runMode=0;
     }
 
+    if(roadNowStart){
+        roadNow=roadOri;
+        roadNowStart=false;
+    }
 
  //   avoidX = (roadOri-roadNow)*roadWidth;
     avoidX=computeAvoidX(roadNow,roadOri,gpsMapLine[PathPoint],ServiceCarStatus.msysparam.vehWidth);

+ 1 - 0
src/decition/decition_brain/decition/decide_gps_00.h

@@ -233,6 +233,7 @@ public:
     double ObsTimeEnd=-1;
     float ObsTimeWidth=1500;
     std::vector<iv::TracePoint> planTrace;
+    bool roadNowStart=true;
 private:
     //  void changeRoad(int roadNum);
 

+ 1 - 1
src/decition/decition_brain_sf/decition/brain.cpp

@@ -372,7 +372,7 @@ void iv::decition::BrainDecition::run() {
     }
     //map
 
-    std::string inRoadAvoid = xp.GetParam("inRoadAvoid","true");  //If Use MPC set true
+    std::string inRoadAvoid = xp.GetParam("inRoadAvoid","false");  //If Use MPC set true
     if(inRoadAvoid == "true")
     {
         ServiceCarStatus.inRoadAvoid = true;

+ 5 - 0
src/decition/decition_brain_sf/decition/decide_gps_00.cpp

@@ -978,6 +978,11 @@ iv::decition::Decition iv::decition::DecideGps00::getDecideFromGPS(GPS_INS now_g
         roadSum = gpsMapLine[PathPoint]->roadSum*3;
     }
 
+    if(roadNowStart){
+        roadNow=roadOri;
+        roadNowStart=false;
+    }
+
     if(ServiceCarStatus.avoidObs){
          gpsMapLine[PathPoint]->runMode=1;
     }else{

+ 2 - 0
src/decition/decition_brain_sf/decition/decide_gps_00.h

@@ -226,6 +226,8 @@ public:
     double ObsTimeEnd=-1;
     float ObsTimeWidth=1500;
     std::vector<iv::TracePoint> planTrace;
+
+    bool roadNowStart=true;
 private:
     //  void changeRoad(int roadNum);
 

+ 108 - 0
src/tool/map_lanetoxodr/adcxodrviewer.pro

@@ -0,0 +1,108 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2019-08-23T15:28:22
+#
+#-------------------------------------------------
+
+QT       += core gui
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+TARGET = adcxodrviewer
+TEMPLATE = app
+
+CONFIG+= c++11
+
+DEFINES += XODRViewer
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which has been marked as deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+QMAKE_LFLAGS += -no-pie
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+
+SOURCES += \
+    filedialogextern.cpp \
+    ivxodrtool.cpp \
+        main.cpp \
+    roaddigit.cpp \
+    myview.cpp \
+    OpenDrive/Junction.cpp \
+    OpenDrive/Lane.cpp \
+    OpenDrive/ObjectSignal.cpp \
+    OpenDrive/OpenDrive.cpp \
+    OpenDrive/OpenDriveXmlParser.cpp \
+    OpenDrive/OpenDriveXmlWriter.cpp \
+    OpenDrive/OtherStructures.cpp \
+    OpenDrive/Road.cpp \
+    OpenDrive/RoadGeometry.cpp \
+    TinyXML/tinystr.cpp \
+    TinyXML/tinyxml.cpp \
+    TinyXML/tinyxmlerror.cpp \
+    TinyXML/tinyxmlparser.cpp \
+    fresnl.cpp \
+    polevl.c \
+    const.cpp \
+    gnss_coordinate_convert.cpp \
+    simpleCustomEvent.cpp \
+    xodrfunc.cpp \
+    xodrscenfunc.cpp \
+    xvmainwindow.cpp
+
+HEADERS += \
+    filedialogextern.h \
+    ivxodrtool.h \
+    roaddigit.h \
+    myview.h \
+    gps_type.h \
+    linedata.h \
+    OpenDrive/Junction.h \
+    OpenDrive/Lane.h \
+    OpenDrive/ObjectSignal.h \
+    OpenDrive/OpenDrive.h \
+    OpenDrive/OpenDriveXmlParser.h \
+    OpenDrive/OpenDriveXmlWriter.h \
+    OpenDrive/OtherStructures.h \
+    OpenDrive/Road.h \
+    OpenDrive/RoadGeometry.h \
+    TinyXML/tinystr.h \
+    TinyXML/tinyxml.h \
+    gnss_coordinate_convert.h \
+    simpleCustomEvent.h \
+    xodrfunc.h \
+    xodrscenfunc.h \
+    xvmainwindow.h
+
+FORMS += \
+    xvmainwindow.ui
+
+
+
+
+
+
+
+QMAKE_CXXFLAGS +=  -g
+
+
+
+
+
+
+DISTFILES += \
+
+
+unix:INCLUDEPATH += /usr/include/eigen3
+win32:INCLUDEPATH += D:\File\soft\eigen
+
+
+RESOURCES += \
+    opendrive.qrc

+ 128 - 0
src/tool/map_lanetoxodr/adcxodrviewer_android.pro

@@ -0,0 +1,128 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2019-08-23T15:28:22
+#
+#-------------------------------------------------
+
+QT       += core gui
+
+QT += androidextras
+
+greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
+
+TARGET = adcxodrviewer
+TEMPLATE = app
+
+CONFIG+= c++11
+
+DEFINES += ANDROID
+
+DEFINES += XODRViewer
+
+# The following define makes your compiler emit warnings if you use
+# any feature of Qt which has been marked as deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+QMAKE_LFLAGS += -no-pie
+
+# You can also make your code fail to compile if you use deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+
+SOURCES += \
+    filedialogextern.cpp \
+    ivxodrtool.cpp \
+        main.cpp \
+    roaddigit.cpp \
+    myview.cpp \
+    OpenDrive/Junction.cpp \
+    OpenDrive/Lane.cpp \
+    OpenDrive/ObjectSignal.cpp \
+    OpenDrive/OpenDrive.cpp \
+    OpenDrive/OpenDriveXmlParser.cpp \
+    OpenDrive/OpenDriveXmlWriter.cpp \
+    OpenDrive/OtherStructures.cpp \
+    OpenDrive/Road.cpp \
+    OpenDrive/RoadGeometry.cpp \
+    TinyXML/tinystr.cpp \
+    TinyXML/tinyxml.cpp \
+    TinyXML/tinyxmlerror.cpp \
+    TinyXML/tinyxmlparser.cpp \
+    fresnl.cpp \
+    polevl.c \
+    const.cpp \
+    gnss_coordinate_convert.cpp \
+    simpleCustomEvent.cpp \
+    xodrfunc.cpp \
+    xodrscenfunc.cpp \
+    xvmainwindow.cpp
+
+HEADERS += \
+    filedialogextern.h \
+    ivxodrtool.h \
+    roaddigit.h \
+    myview.h \
+    gps_type.h \
+    linedata.h \
+    OpenDrive/Junction.h \
+    OpenDrive/Lane.h \
+    OpenDrive/ObjectSignal.h \
+    OpenDrive/OpenDrive.h \
+    OpenDrive/OpenDriveXmlParser.h \
+    OpenDrive/OpenDriveXmlWriter.h \
+    OpenDrive/OtherStructures.h \
+    OpenDrive/Road.h \
+    OpenDrive/RoadGeometry.h \
+    TinyXML/tinystr.h \
+    TinyXML/tinyxml.h \
+    gnss_coordinate_convert.h \
+    simpleCustomEvent.h \
+    xodrfunc.h \
+    xodrscenfunc.h \
+    xvmainwindow.h
+
+FORMS += \
+    xvmainwindow.ui
+
+
+
+
+
+
+
+QMAKE_CXXFLAGS +=  -g
+
+
+
+
+
+
+DISTFILES += \ \
+    android/AndroidManifest.xml \
+    android/build.gradle \
+    android/gradle/wrapper/gradle-wrapper.jar \
+    android/gradle/wrapper/gradle-wrapper.properties \
+    android/gradlew \
+    android/gradlew.bat \
+    android/res/values/libs.xml \
+    android/src/an/qt/extendsQtWithJava/ExtendsQtNative.java \
+    android/src/an/qt/extendsQtWithJava/ExtendsQtWithJava.java
+#    android/src/an/qt/ExtendsQtNative.java \
+ #    android/src/an/qt/ExtendsQtWithJava.java
+
+
+unix:INCLUDEPATH += /usr/include/eigen3
+win32:INCLUDEPATH += D:\File\soft\eigen
+
+
+RESOURCES += \
+    opendrive.qrc
+
+contains(ANDROID_TARGET_ARCH,arm64-v8a) {
+    ANDROID_PACKAGE_SOURCE_DIR = \
+        $$PWD/android
+}

+ 91 - 0
src/tool/map_lanetoxodr/android/AndroidManifest.xml

@@ -0,0 +1,91 @@
+<?xml version="1.0"?>
+<manifest package="adc.iv.xodrviewer" xmlns:android="http://schemas.android.com/apk/res/android" android:versionName="-- %%INSERT_VERSION_NAME%% --" android:versionCode="-- %%INSERT_VERSION_CODE%% --" android:installLocation="auto">
+    <uses-sdk android:minSdkVersion="21" android:targetSdkVersion="28"/>
+
+    <!-- The following comment will be replaced upon deployment with default permissions based on the dependencies of the application.
+         Remove the comment if you do not require these default permissions. -->
+    <!-- %%INSERT_PERMISSIONS -->
+
+    <!-- The following comment will be replaced upon deployment with default features based on the dependencies of the application.
+         Remove the comment if you do not require these default features. -->
+    <!-- %%INSERT_FEATURES -->
+
+    <supports-screens android:largeScreens="true" android:normalScreens="true" android:anyDensity="true" android:smallScreens="true"/>
+
+    <application android:hardwareAccelerated="true" android:name="org.qtproject.qt5.android.bindings.QtApplication" android:label="XODRViewer" android:icon="@drawable/icon">
+        <activity android:configChanges="orientation|uiMode|screenLayout|screenSize|smallestScreenSize|layoutDirection|locale|fontScale|keyboard|keyboardHidden|navigation|mcc|mnc|density" android:name="an.qt.extendsQtWithJava.ExtendsQtWithJava" android:label="XODRViewer" android:screenOrientation="unspecified" android:launchMode="singleTop">
+            <intent-filter>
+                <action android:name="android.intent.action.MAIN"/>
+                <category android:name="android.intent.category.LAUNCHER"/>
+            </intent-filter>
+
+            <!-- Application arguments -->
+            <!-- meta-data android:name="android.app.arguments" android:value="arg1 arg2 arg3"/ -->
+            <!-- Application arguments -->
+
+            <meta-data android:name="android.app.lib_name" android:value="-- %%INSERT_APP_LIB_NAME%% --"/>
+            <meta-data android:name="android.app.qt_sources_resource_id" android:resource="@array/qt_sources"/>
+            <meta-data android:name="android.app.repository" android:value="default"/>
+            <meta-data android:name="android.app.qt_libs_resource_id" android:resource="@array/qt_libs"/>
+            <meta-data android:name="android.app.bundled_libs_resource_id" android:resource="@array/bundled_libs"/>
+            <!-- Deploy Qt libs as part of package -->
+            <meta-data android:name="android.app.bundle_local_qt_libs" android:value="-- %%BUNDLE_LOCAL_QT_LIBS%% --"/>
+            <meta-data android:name="android.app.bundled_in_lib_resource_id" android:resource="@array/bundled_in_lib"/>
+            <meta-data android:name="android.app.bundled_in_assets_resource_id" android:resource="@array/bundled_in_assets"/>
+            <!-- Run with local libs -->
+            <meta-data android:name="android.app.use_local_qt_libs" android:value="-- %%USE_LOCAL_QT_LIBS%% --"/>
+            <meta-data android:name="android.app.libs_prefix" android:value="/data/local/tmp/qt/"/>
+            <meta-data android:name="android.app.load_local_libs" android:value="-- %%INSERT_LOCAL_LIBS%% --"/>
+            <meta-data android:name="android.app.load_local_jars" android:value="-- %%INSERT_LOCAL_JARS%% --"/>
+            <meta-data android:name="android.app.static_init_classes" android:value="-- %%INSERT_INIT_CLASSES%% --"/>
+            <!-- Used to specify custom system library path to run with local system libs -->
+            <!-- <meta-data android:name="android.app.system_libs_prefix" android:value="/system/lib/"/> -->
+            <!--  Messages maps -->
+            <meta-data android:value="@string/ministro_not_found_msg" android:name="android.app.ministro_not_found_msg"/>
+            <meta-data android:value="@string/ministro_needed_msg" android:name="android.app.ministro_needed_msg"/>
+            <meta-data android:value="@string/fatal_error_msg" android:name="android.app.fatal_error_msg"/>
+            <meta-data android:value="@string/unsupported_android_version" android:name="android.app.unsupported_android_version"/>
+            <!--  Messages maps -->
+
+            <!-- Splash screen -->
+            <!-- Orientation-specific (portrait/landscape) data is checked first. If not available for current orientation,
+                 then android.app.splash_screen_drawable. For best results, use together with splash_screen_sticky and
+                 use hideSplashScreen() with a fade-out animation from Qt Android Extras to hide the splash screen when you
+                 are done populating your window with content. -->
+            <!-- meta-data android:name="android.app.splash_screen_drawable_portrait" android:resource="@drawable/logo_portrait" / -->
+            <!-- meta-data android:name="android.app.splash_screen_drawable_landscape" android:resource="@drawable/logo_landscape" / -->
+            <!-- meta-data android:name="android.app.splash_screen_drawable" android:resource="@drawable/logo"/ -->
+            <!-- meta-data android:name="android.app.splash_screen_sticky" android:value="true"/ -->
+            <!-- Splash screen -->
+
+            <!-- Background running -->
+            <!-- Warning: changing this value to true may cause unexpected crashes if the
+                          application still try to draw after
+                          "applicationStateChanged(Qt::ApplicationSuspended)"
+                          signal is sent! -->
+            <meta-data android:name="android.app.background_running" android:value="false"/>
+            <!-- Background running -->
+
+            <!-- auto screen scale factor -->
+            <meta-data android:name="android.app.auto_screen_scale_factor" android:value="false"/>
+            <!-- auto screen scale factor -->
+
+            <!-- extract android style -->
+            <!-- available android:values :
+                * default - In most cases this will be the same as "full", but it can also be something else if needed, e.g., for compatibility reasons
+                * full - useful QWidget & Quick Controls 1 apps
+                * minimal - useful for Quick Controls 2 apps, it is much faster than "full"
+                * none - useful for apps that don't use any of the above Qt modules
+                -->
+            <meta-data android:name="android.app.extract_android_style" android:value="default"/>
+            <!-- extract android style -->
+    </activity>
+
+    <!-- For adding service(s) please check: https://wiki.qt.io/AndroidServices -->
+
+    </application>
+
+<uses-permission android:name="android.permission.READ_EXTERNAL_STORAGE"/>
+    <uses-permission android:name="android.permission.WRITE_EXTERNAL_STORAGE"/>
+    <uses-permission android:name="android.permission.ACCESS_CHECKIN_PROPERTIES"/>
+</manifest>

BIN
src/tool/map_lanetoxodr/android/libs/android-support-v4.jar


+ 1 - 0
src/tool/map_lanetoxodr/android/libs/android-support-v4.jar.properties

@@ -0,0 +1 @@
+src = E:\\ProgramFiles\\Tools\\Android\\android-sdk\\extras\\android\\m2repository\\com\\android\\support\\support-v4

+ 12 - 0
src/tool/map_lanetoxodr/android/src/an/qt/extendsQtWithJava/ExtendsQtNative.java

@@ -0,0 +1,12 @@
+package an.qt.extendsQtWithJava;
+import java.lang.String;
+
+public class ExtendsQtNative
+{
+    //public static native String GetQtVersion();
+    //public static native void OnLocationReady(int result, double longitude, double latitude);
+    //public static native void OnImageCaptured(int result, String filePath);
+    //public static native void onFileManager(int result, String fileurl);
+    public static native void onFileManager(int result, String[] fileurls);
+
+}

+ 348 - 0
src/tool/map_lanetoxodr/android/src/an/qt/extendsQtWithJava/ExtendsQtWithJava.java

@@ -0,0 +1,348 @@
+package an.qt.extendsQtWithJava;
+import android.Manifest;
+import android.app.Activity;
+import android.app.Notification;
+import android.app.NotificationManager;
+import android.content.ClipData;
+import android.content.ContentUris;
+import android.content.Context;
+import android.content.Intent;
+import android.content.pm.PackageManager;
+import android.database.Cursor;
+import android.app.PendingIntent;
+import android.widget.Toast;
+import android.os.Handler;
+import android.os.Message;
+import android.util.Log;
+import android.net.ConnectivityManager;
+import android.net.NetworkInfo;
+import android.net.Uri;
+import android.location.LocationManager;
+import android.location.Criteria;
+import android.provider.Settings;
+import android.support.v4.app.ActivityCompat;
+import android.support.v4.content.ContextCompat;
+import android.location.Location;
+import android.location.LocationListener;
+import android.location.LocationProvider;
+import java.lang.ClassLoader;
+import dalvik.system.DexClassLoader;
+import java.lang.reflect.Field;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.List;
+import java.util.stream.Stream;
+
+import android.os.Build;
+import android.os.Bundle;
+import android.os.Environment;
+import java.io.File;
+
+import android.provider.DocumentsContract;
+import android.provider.MediaStore;
+
+
+public class ExtendsQtWithJava extends org.qtproject.qt5.android.bindings.QtActivity
+{
+    //private final static int GET_LOCATION_REQUEST_CODE = 1;
+    //private final static int CAPTURE_IMAGE_REQUEST_CODE = 2;
+    private final static int FILE_MANAGER_REQUEST_CODE = 3;
+    final private int REQUEST_CODE_ASK_PERMISSIONS = 123;
+   // private static NotificationManager m_notificationManager;
+    private static ExtendsQtWithJava m_instance;
+    private static Class m_nativeClass = null;
+    private final static String TAG = "extendsQt";
+    public LocationManager m_lm = null;
+
+    public ExtendsQtWithJava(){
+        Log.d(TAG, "ExtendsQtWithJava constructor");
+        m_instance = this;
+    }
+
+    /**
+     * 获得类的成员变量值,包括私有成员
+     * @param instance 被调用的类
+     * @param variableName 成员变量名
+     *
+     */
+    public static Object get(Object instance, String variableName)
+    {
+        Class targetClass = instance.getClass().getSuperclass();
+        org.qtproject.qt5.android.bindings.QtActivity superInst = (org.qtproject.qt5.android.bindings.QtActivity)targetClass.cast(instance);
+        Log.d(TAG, "super class name - " + targetClass.getName() + " super instance -" + superInst);
+        Field field;
+        try {
+            field = targetClass.getDeclaredField(variableName);
+            Log.d(TAG, "field name - " + field.getName());
+            field.setAccessible(true);//访问私有必须调用
+            return field.get(superInst);
+        } catch (Exception e) {
+            e.printStackTrace();
+            return null;
+        }
+    }
+
+    public static void loadExtendsQtNative(){
+    if(m_nativeClass == null){
+        DexClassLoader loader = (DexClassLoader)get(m_instance, "m_classLoader");
+        Log.d(TAG, "loader - " + loader);
+        if(loader != null){
+            try{
+                m_nativeClass = loader.loadClass("an.qt.extendsQtWithJava.ExtendsQtNative");
+                Log.d(TAG, "load ExtendsQtNative OK!");
+            }catch(ClassNotFoundException e){
+                Log.d(TAG, "load ExtendsQtNative failed");
+            }
+        }
+    }
+    }
+
+    protected  List<Uri> getUris(Intent data){
+        List<Uri> uris = new ArrayList<Uri>();
+        if (Build.VERSION.SDK_INT >= Build.VERSION_CODES.JELLY_BEAN) {
+            ClipData clipData = data.getClipData();
+            if (null != clipData) {
+                for (int i = 0; i < clipData.getItemCount(); i++) {
+                    ClipData.Item item = clipData.getItemAt(i);
+                    uris.add(item.getUri());
+                }
+            } else {
+                uris.add(data.getData());
+            }
+        } else {
+                uris.add(data.getData());
+        }
+        return uris;
+    }
+
+
+    public static void fileManagerActivity(boolean multi){
+        Log.d(TAG, "fileManagerActivity1");
+        //m_instance.startActivity(new Intent(action));
+        Intent intent = new Intent(Intent.ACTION_GET_CONTENT);
+        intent.setType("*/*");//设置类型,我这里是任意类型,任意后缀的可以这样写。
+        intent.addCategory(Intent.CATEGORY_OPENABLE);
+        intent.putExtra(Intent.EXTRA_ALLOW_MULTIPLE, multi == true);//多选
+        intent.putExtra(Intent.EXTRA_LOCAL_ONLY, true);
+//        intent.putExtra("pointer", 12345678);//无法用putExtra 传递数据在 onActivityResult 中接收,放在下面的it中也不行
+//        Bundle b=new Bundle();
+//        b.putString("listenB", "zp");
+//        intent.putExtras(b);
+
+        //Intent it = Intent.createChooser(intent, "choose file");
+        m_instance.startActivityForResult(intent,FILE_MANAGER_REQUEST_CODE);
+    }
+
+    @Override
+    protected void onActivityResult(int requestCode, int resultCode, Intent data){
+        //super.onActivityResult(requestCode, resultCode, data);
+        Log.d(TAG, "onActivityResult:"+requestCode+";"+resultCode);
+        switch(requestCode){
+        case FILE_MANAGER_REQUEST_CODE:
+        {
+                String arr[] = {};
+            if (resultCode == Activity.RESULT_OK) {
+
+//            data.getIntExtra("pointer", 0);//无法接收数据
+//            Bundle b=data.getExtras();
+
+            //doFileMenageryResult(requestCode,resultCode, data);
+/*            if (resultCode == Activity.RESULT_OK) {//是否选择,没选择就不会继续
+                Uri uri = data.getData();//得到uri,后面就是将uri转化成file的过程。
+                Log.d(TAG, "uri:" + uri);
+                Log.d(TAG, "uri Scheme:" + uri.getScheme());
+                String path = uri.getPath();//= getPath(this, uri);
+
+                if ("file".equalsIgnoreCase(uri.getScheme())){//使用第三方应用打开
+                        Log.d(TAG, "uri:---1");
+                    path = uri.getPath();
+                }else if (Build.VERSION.SDK_INT > Build.VERSION_CODES.KITKAT) {//4.4+
+                        Log.d(TAG, "uri:---2");
+                    path = getPath(this, uri);
+                }
+                Log.d(TAG, "fpath:" + path);
+
+
+                ExtendsQtNative.onFileManager(resultCode, path);
+
+                */
+                List<Uri> uris = getUris(data);
+               List<String> paths = new ArrayList<String>();
+               for(Uri uri : uris){
+                       String path = "";
+                   if ("file".equalsIgnoreCase(uri.getScheme())){//使用第三方应用打开
+                       Log.d(TAG, "uri:---1");
+                           path = uri.getPath();
+                       }else if (Build.VERSION.SDK_INT > Build.VERSION_CODES.KITKAT) {//4.4+
+                           Log.d(TAG, "uri:---2");
+                           path = getPath(this, uri);
+                       }
+                                Log.d(TAG, "fpath:" + path);
+                   if(path!=null && !path.isEmpty()){
+                       paths.add(path);
+                   }
+               }
+
+
+               Log.d(TAG, "fpaths:" + paths.toString());
+
+               arr = paths.toArray(new String[paths.size()]);
+               Log.d(TAG, "arr:" + arr.toString());
+
+               ExtendsQtNative.onFileManager(resultCode, arr);
+            }else if(resultCode == Activity.RESULT_CANCELED ){
+                //String arr[] = {};
+                ExtendsQtNative.onFileManager(resultCode,  arr);
+            }
+        }
+
+            break;
+        default:
+            super.onActivityResult(requestCode, resultCode, data);
+        }
+    }
+
+/**
+ * 专为Android4.4设计的从Uri获取文件绝对路径,以前的方法已不好使
+ */
+public String getPath(final Context context, final Uri uri) {
+        Log.d(TAG, "getPath:---1");
+    final boolean isKitKat = Build.VERSION.SDK_INT >= Build.VERSION_CODES.KITKAT;
+    Log.d(TAG, "getPath:---2-getAuthority:"+uri.getAuthority());
+    // DocumentProvider
+    if (isKitKat && DocumentsContract.isDocumentUri(context, uri)) {
+        Log.d(TAG, "getPath:---3");
+        // ExternalStorageProvider
+        if (isExternalStorageDocument(uri)) {
+            final String docId = DocumentsContract.getDocumentId(uri);
+            final String[] split = docId.split(":");
+            final String type = split[0];
+
+            if ("primary".equalsIgnoreCase(type)) {
+                return Environment.getExternalStorageDirectory() + "/" + split[1];
+            }
+        }
+        // DownloadsProvider
+        else if (isDownloadsDocument(uri)) {
+
+            final String id = DocumentsContract.getDocumentId(uri);
+            final Uri contentUri = ContentUris.withAppendedId(
+                    Uri.parse("content://downloads/public_downloads"), Long.valueOf(id));
+
+            return getDataColumn(context, contentUri, null, null);
+        }
+        // MediaProvider
+        else if (isMediaDocument(uri)) {
+                Log.d(TAG, "getPath:---4");
+            final String docId = DocumentsContract.getDocumentId(uri);
+            Log.d(TAG, "docId:"+docId);
+            final String[] split = docId.split(":");
+            final String type = split[0];
+            Log.d(TAG, "docId split:"+Arrays.toString(split));
+            Uri contentUri = null;
+            if ("image".equals(type)) {
+                contentUri = MediaStore.Images.Media.EXTERNAL_CONTENT_URI;
+            } else if ("video".equals(type)) {
+                contentUri = MediaStore.Video.Media.EXTERNAL_CONTENT_URI;
+            } else if ("audio".equals(type)) {
+                contentUri = MediaStore.Audio.Media.EXTERNAL_CONTENT_URI;
+            }
+
+            final String selection = "_id=?";
+            final String[] selectionArgs = new String[]{split[1]};
+            Log.d(TAG, "contentUri:"+contentUri);
+
+            return getDataColumn(context, contentUri, selection, selectionArgs);
+        }
+    }
+    // MediaStore (and general)
+    else if ("content".equalsIgnoreCase(uri.getScheme())) {
+        return getDataColumn(context, uri, null, null);
+    }
+    // File
+    else if ("file".equalsIgnoreCase(uri.getScheme())) {
+        return uri.getPath();
+    }
+    return null;
+}
+
+/**
+ * Get the value of the data column for this Uri. This is useful for
+ * MediaStore Uris, and other file-based ContentProviders.
+ *
+ * @param context       The context.
+ * @param uri           The Uri to query.
+ * @param selection     (Optional) Filter used in the query.
+ * @param selectionArgs (Optional) Selection arguments used in the query.
+ * @return The value of the _data column, which is typically a file path.
+ */
+public String getDataColumn(Context context, Uri uri, String selection,
+                            String[] selectionArgs) {
+        Log.d(TAG, "getDataColumn:"+uri+";"+selection+";"+Arrays.toString(selectionArgs));
+//content://media/external/images/media;  _id=?;[715746]
+    Cursor cursor = null;
+    final String column = "_data";
+    final String[] projection = {column};
+
+    try {
+/**********权限校验需要 >=sdk23 版本*****************************************/
+        int hasWriteContactsPermisson = ContextCompat.checkSelfPermission(context,
+                        android.Manifest.permission.READ_EXTERNAL_STORAGE);
+        Log.d(TAG, "hasWriteContactsPermisson:"+hasWriteContactsPermisson);
+        if(hasWriteContactsPermisson !=
+            PackageManager.PERMISSION_GRANTED)
+        {
+                ActivityCompat.requestPermissions(m_instance,new String[]
+                {Manifest.permission.WRITE_CONTACTS},
+                REQUEST_CODE_ASK_PERMISSIONS);
+
+            return "";
+        }
+/********************************/
+        Log.d(TAG, "getDataColumn--1");
+        cursor = context.getContentResolver().query(uri, projection, selection, selectionArgs,
+                null);
+        Log.d(TAG, "getDataColumn--2");
+        if (cursor != null && cursor.moveToFirst()) {
+                Log.d(TAG, "getDataColumn--3");
+            final int column_index = cursor.getColumnIndexOrThrow(column);
+            Log.d(TAG, "getDataColumn--4");
+            return cursor.getString(column_index);
+        }
+    } catch(Exception e){
+        Log.d(TAG, "getDataColumn err:"+e.getMessage());
+    }finally {
+        if (cursor != null)
+            cursor.close();
+    }
+    return "null";
+}
+
+
+/**
+ * @param uri The Uri to check.
+ * @return Whether the Uri authority is ExternalStorageProvider.
+ */
+public boolean isExternalStorageDocument(Uri uri) {
+    return "com.android.externalstorage.documents".equals(uri.getAuthority());
+}
+
+/**
+ * @param uri The Uri to check.
+ * @return Whether the Uri authority is DownloadsProvider.
+ */
+public boolean isDownloadsDocument(Uri uri) {
+    return "com.android.providers.downloads.documents".equals(uri.getAuthority());
+}
+
+/**
+ * @param uri The Uri to check.
+ * @return Whether the Uri authority is MediaProvider.
+ */
+public boolean isMediaDocument(Uri uri) {
+    return "com.android.providers.media.documents".equals(uri.getAuthority());
+}
+
+
+}
+

+ 136 - 0
src/tool/map_lanetoxodr/filedialogextern.cpp

@@ -0,0 +1,136 @@
+#include "filedialogextern.h"
+#include "simpleCustomEvent.h"
+#include <QEvent>
+#include <QCoreApplication>
+
+#ifdef ANDROID
+#include <QtAndroidExtras/QAndroidJniObject>
+#include <QFile>
+#include<unistd.h>
+//#include <QGuiApplication>
+#include <QAndroidJniEnvironment>
+#else
+#include <QFileDialog>
+#include <QDir>
+#endif
+
+#include <QMessageBox>
+
+#include <QDebug>
+#define DEBUG     qDebug()<<__func__<<__LINE__
+
+static QObject *g_listener = 0;
+
+FileDialogExtern::FileDialogExtern(QObject *parent) : QObject(parent)
+{
+
+}
+
+
+bool FileDialogExtern::event(QEvent *e)
+{
+#ifdef ANDROID
+    if(e->type() == SimpleCustomEvent::eventType())
+    {
+        SimpleCustomEvent *sce = (SimpleCustomEvent*)e;
+        qDebug()<<"FileDialogExtern::event:"<<sce->m_requestCode<<sce->m_resultCode;
+        if(sce->m_requestCode == 3){
+
+
+            if(sce->m_resultCode == -1){
+                QStringList paths = sce->m_msg.toStringList();
+                DEBUG<<paths.count()<<paths;
+                if(paths.isEmpty()) return QObject::event(e);
+                setCurrentFiles(paths);
+                setCurrentFile(paths.at(0));
+//                QMessageBox::information(this,"warn","hello",QMessageBox::YesAll);
+                emit accepted();
+            }else if (sce->m_resultCode == 0) {
+                DEBUG<<"cancel";
+                emit rejected();
+            }
+
+        }/*else
+        {
+            m_captureState->setText("cancel");
+        }*/
+        return true;
+    }
+#endif
+    return QObject::event(e);
+}
+
+
+
+bool FileDialogExtern::open(){
+DEBUG;
+
+#ifdef ANDROID
+
+    //QAndroidJniObject javaAction = QAndroidJniObject::fromString(name);
+    g_listener = this;
+    QAndroidJniObject::callStaticMethod<void>("an/qt/extendsQtWithJava/ExtendsQtWithJava",
+                                       "fileManagerActivity",
+                                       "(Z)V",(m_fileMode == OpenFiles));
+
+
+#else
+
+QString fdir = m_folder.isEmpty()?QDir::currentPath():m_folder;
+QStringList fpaths;
+if(m_fileMode == OpenFile){
+    QString fpath = QFileDialog::getOpenFileName(nullptr,m_title,fdir,"all file(*)");
+    if(!fpath.isEmpty())
+        fpaths.push_back(fpath);
+}else if (m_fileMode == OpenFiles) {
+    fpaths = QFileDialog::getOpenFileNames(nullptr,m_title,fdir,"all file(*)");
+}
+DEBUG<<fpaths.count()<<fpaths;
+if(!fpaths.isEmpty()){
+    setCurrentFiles(fpaths);
+    setCurrentFile(fpaths.at(0));
+    emit accepted();
+}else {
+    emit rejected();
+}
+#endif
+
+    return true;
+}
+
+#ifdef ANDROID
+void onFileManager(JNIEnv *env, jobject thiz,int result, jobjectArray fileUrls)
+{
+    qDebug() << "onFileManager, result - " << result ;
+   int length =  env->GetArrayLength(fileUrls);
+   QStringList paths;
+   int req = 3;
+   int ret = result;
+   if(result == -1){
+       //ret = 3;
+
+       for (int i=0;i<length;i++) {
+           //jstring fileUrl= dynamic_cast<jstring>(env->GetObjectArrayElement(fileUrls,i));
+
+           QString path=QAndroidJniObject::fromLocalRef(env->GetObjectArrayElement(fileUrls,i)).toString();
+
+          // qDebug() << "onFileManager, result - " << result << " fileUrl - " << fileUrl;
+
+           //jboolean copy = false;
+            //const char *nativeString = env->GetStringUTFChars(fileUrl, &copy);
+            //qDebug() << "onFileManager, nativeString - " << nativeString;
+//            QString path = nativeString;
+//            env->ReleaseStringUTFChars(fileUrl, nativeString);
+            if(!path.isEmpty() && QFile::exists(path))
+                paths.push_back(path);
+            qDebug() << "onFileManager, path - " << path;
+       }
+   }else if(result != 0){
+       ret = -3;
+       qDebug() << "could not read the captured file!";
+   }
+DEBUG<<paths;
+    //QGuiApplication::postEvent(g_listener, new SimpleCustomEvent(ret, image));
+    QCoreApplication::postEvent(g_listener, new SimpleCustomEvent(req,ret, paths));
+}
+#endif

+ 56 - 0
src/tool/map_lanetoxodr/filedialogextern.h

@@ -0,0 +1,56 @@
+#ifndef FILEDIALOGEXTERN_H
+#define FILEDIALOGEXTERN_H
+
+#include <QObject>
+
+class FileDialogExtern : public QObject
+{
+    Q_OBJECT
+    Q_ENUMS(FileMode)
+    Q_PROPERTY(NOTIFY accepted)
+    Q_PROPERTY(NOTIFY rejected)
+    Q_PROPERTY(QString title READ title WRITE setTitle NOTIFY titleChanged)
+    Q_PROPERTY(QString folder READ folder WRITE setFolder NOTIFY folderChanged)
+    Q_PROPERTY(QString currentFile READ currentFile WRITE setCurrentFile NOTIFY currentFileChanged)
+    Q_PROPERTY(QStringList currentFiles READ currentFiles WRITE setCurrentFiles NOTIFY currentFilesChanged)
+    Q_PROPERTY(FileMode fileMode READ fileMode WRITE setFileMode NOTIFY fileModeChanged)
+
+
+public:
+    enum FileMode{OpenFile,OpenFiles,Saveile};
+    explicit FileDialogExtern(QObject *parent = nullptr);
+    bool event(QEvent *);
+
+    Q_INVOKABLE bool open();
+
+    QString title() const{return m_title;}
+    QString folder() const{return m_folder;}
+    QString currentFile() const{return m_currentFile;}
+    QStringList currentFiles() const{return m_currentFiles;}
+    FileMode fileMode() const{return m_fileMode;}
+
+signals:
+    void accepted();
+    void rejected();
+    void titleChanged(QString title);
+    void folderChanged(QString folder);
+    void currentFilesChanged(QStringList currentFiles);
+    void currentFileChanged(QString currentFile);
+    void fileModeChanged(FileMode fileMode);
+
+public slots:
+    void setTitle(const QString &title){m_title = title; emit titleChanged(m_title);}
+    void setFolder(const QString &folder){m_folder = folder; emit folderChanged(m_folder);}
+    void setCurrentFile(const QString &currentFile){m_currentFile = currentFile; emit currentFileChanged(m_currentFile);}
+    void setCurrentFiles(const QStringList &currentFiles){m_currentFiles = currentFiles; emit currentFilesChanged(m_currentFiles);}
+    void setFileMode(const FileMode &fileMode){m_fileMode = fileMode; emit fileModeChanged(m_fileMode);}
+
+private:
+    QString m_title;
+    QString m_folder;
+    QString m_currentFile;
+    QStringList m_currentFiles;
+    FileMode m_fileMode;
+};
+
+#endif // FILEDIALOGEXTERN_H

+ 58 - 2
src/tool/map_lanetoxodr/main.cpp

@@ -1,14 +1,70 @@
+
+#ifdef XODRViewer
+#include "xvmainwindow.h"
+#else
 #include "mainwindow.h"
+#endif
+
 #include <QApplication>
 
-#include "ivbacktrace.h"
+
+#ifdef ANDROID
+#include <QAndroidJniEnvironment>
+#include <QtAndroid>
+//#include <QAndr
+#include <QAndroidJniObject>
+
+#endif
+
+
+#ifdef XODRViewer
+#include "filedialogextern.h"
+#endif
+#ifdef ANDROID
+#include "simpleCustomEvent.h"
+#endif
+
+
+
+
+
+#ifdef ANDROID
+
+bool requestPermission() {
+   QtAndroid::PermissionResult  r = QtAndroid::checkPermission("android.permission.WRITE_EXTERNAL_STORAGE");
+    if(r == QtAndroid::PermissionResult::Denied) {
+        QtAndroid::requestPermissionsSync( QStringList() << "android.permission.WRITE_EXTERNAL_STORAGE" );
+        r = QtAndroid::checkPermission("android.permission.WRITE_EXTERNAL_STORAGE");
+        if(r == QtAndroid::PermissionResult::Denied) {
+             return false;
+        }
+   }
+   return true;
+}
+
+#endif
+
+
 
 int main(int argc, char *argv[])
 {
-    RegisterIVBackTrace();
 
     QApplication a(argc, argv);
+
+#ifdef ANDROID
+
+    requestPermission();
+
+
+    registerNativeMethods();
+
+#endif
+
+#ifdef XODRViewer
+    XVMainWindow w;
+#else
     MainWindow w;
+#endif
     w.show();
     w.resize(1280,800);
 

+ 98 - 2
src/tool/map_lanetoxodr/mainwindow.cpp

@@ -54,6 +54,10 @@ MainWindow::MainWindow(QWidget *parent) :
 
     scene = new QGraphicsScene;
 
+//    mpscene = new  QGraphicsScene;//(-300, -300, 600, 600);
+    mpscene = new  QGraphicsScene(0,0,VIEW_WIDTH,VIEW_HEIGHT);
+    mpscene->setBackgroundBrush(Qt::darkGreen);
+
 
  //    painter->begin(image);
 
@@ -370,6 +374,16 @@ void MainWindow::ExecPainter()
 void MainWindow::paintEvent(QPaintEvent *)
 {
 
+    if(mnViewMode == 1)
+    {
+        if(mbRefresh)
+        {
+ //           UpdateScene();
+        }
+        myview->setScene(mpscene);
+        myview->show();
+        return;
+    }
     if(mbRefresh)
     {
         ExecPainter();
@@ -422,6 +436,21 @@ void MainWindow::CreateTab1View(QTabWidget * p)
     int nLEWidth = mnFontHeight * 6;
     int nLEHeight = mnFontHeight * 3/2;
 
+    pLabel = new QLabel(pGroup);
+    pLabel->setText("View Mode");
+    pLabel->setGeometry(nXPos,nYPos,nLEWidth,nLEHeight);
+    nXPos = nXPos + nSpace;
+
+    pCB = new QComboBox(pGroup);
+    pCB->addItem("Line");
+    pCB->addItem("Scene");
+    pCB->setCurrentIndex(0);
+    pCB->setGeometry(nXPos,nYPos,nLEWidth,nLEHeight);
+    connect(pCB,SIGNAL(currentIndexChanged(int)),this,SLOT(onViewModeChange(int)));
+
+    nXPos = 10;
+    nYPos = nYPos + mnFontHeight * 3;
+
     pLabel = new QLabel(pGroup);
     pLabel->setText("Lat0");
     pLabel->setGeometry(nXPos,nYPos,nLEWidth,nLEHeight);
@@ -1168,8 +1197,11 @@ void MainWindow::onClickXY(double x, double y)
     double lon,lat;
     selx = mClickX;
     sely = mClickY * (-1);
-    selx = selx/((double )mnfac);
-    sely = sely/((double)mnfac);
+    if(mnViewMode == 0)
+    {
+        selx = selx/((double )mnfac);
+        sely = sely/((double)mnfac);
+    }
     mpLE_SelX->setText(QString::number(selx,'f',3));
     mpLE_SelY->setText(QString::number(sely,'f',3));
 
@@ -5030,3 +5062,67 @@ void MainWindow::on_actionSplit_Road_triggered()
 {
 
 }
+
+void MainWindow::UpdateScene()
+{
+
+    int i;
+    int nsize = mvectorviewitem.size();
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+        delete mvectorviewitem.at(i);
+    }
+    mvectorviewitem.clear();
+
+    nsize = mxodr.GetRoadCount();
+
+    std::vector<RoadDigit> xvectorrd;
+    for(i=0;i<nsize;i++)
+    {
+        RoadDigit xrd(mxodr.GetRoad(i),10.0);
+        xvectorrd.push_back(xrd);
+ //       UpdateSceneRoad(mxodr.GetRoad(i));
+//        qDebug("update road %d",i);
+    }
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectorlanepath = xodrscenfunc::GetRoadLaneItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectorlanepath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectorlanepath[j];
+            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectormarkpath = xodrscenfunc::GetRoadMarkItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectormarkpath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectormarkpath[j];
+            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+    mbRefresh = false;
+}
+
+
+void MainWindow::onViewModeChange(int index)
+{
+    if(index == 1)
+    {
+       UpdateScene();
+    }
+    mnViewMode = index;
+    mbRefresh = true;
+    update();
+}

+ 15 - 0
src/tool/map_lanetoxodr/mainwindow.h

@@ -67,6 +67,10 @@ using namespace Eigen;
 
 #include "xodrmake.h"
 
+#include "roaddigit.h"
+
+#include "xodrscenfunc.h"
+
 namespace Ui {
 class MainWindow;
 }
@@ -88,6 +92,9 @@ private:
     QTimer *timer;
     QGraphicsScene *scene;
 
+    QGraphicsScene * mpscene;
+
+
 public:
     static void ComboToString(std::string strroadid,QComboBox * pCB);
 
@@ -185,6 +192,8 @@ private slots:
 
     void on_actionSplit_Road_triggered();
 
+    void onViewModeChange(int index);
+
 private:
 
 
@@ -385,6 +394,12 @@ private:
     void updateCBRoad();
     void updateJunction();
 
+    int mnViewMode = 0; //Use Scene
+
+    void UpdateScene();
+
+    std::vector<QGraphicsPathItem *> mvectorviewitem;
+
 
 };
 

+ 6 - 3
src/tool/map_lanetoxodr/map_lanetoxodr.pro

@@ -41,6 +41,7 @@ SOURCES += \
     ivxodrtool.cpp \
         main.cpp \
         mainwindow.cpp \
+    roaddigit.cpp \
     roadeditdialog.cpp \
     roadviewitem.cpp \
     speeddialog.cpp \
@@ -73,7 +74,8 @@ SOURCES += \
     geofit.cpp \
     circlefitting.cpp \
     xodrfunc.cpp \
-    xodrmake.cpp
+    xodrmake.cpp \
+    xodrscenfunc.cpp
 
 HEADERS += \
     autoconnect.h \
@@ -89,6 +91,7 @@ HEADERS += \
     ivxodrtool.h \
         mainwindow.h \
     rawtype.h \
+    roaddigit.h \
     roadeditdialog.h \
     roadviewitem.h \
     speeddialog.h \
@@ -99,7 +102,6 @@ HEADERS += \
     myview.h \
     boost.h \
     gps_type.h \
-    linedata.h \
     OpenDrive/Junction.h \
     OpenDrive/Lane.h \
     OpenDrive/ObjectSignal.h \
@@ -118,7 +120,8 @@ HEADERS += \
     geofit.h \
     circlefitting.h \
     xodrfunc.h \
-    xodrmake.h
+    xodrmake.h \
+    xodrscenfunc.h
 
 FORMS += \
         dialogaddroadfromrtk.ui \

+ 75 - 0
src/tool/map_lanetoxodr/myview.cpp

@@ -9,8 +9,15 @@ MyView::MyView(QWidget *parent) :
     beishu(1.00000)
 {
     setDragMode(QGraphicsView::ScrollHandDrag);
+
+//    grabGesture(Qt::PanGesture);
+    grabGesture(Qt::PinchGesture);
+ //   grabGesture(Qt::SwipeGesture);
 }
 
+
+
+
 void MyView::mousePressEvent(QMouseEvent *event)
 {
 //    qDebug("x is %d",event->pos().x());
@@ -19,6 +26,7 @@ void MyView::mousePressEvent(QMouseEvent *event)
 }
 void MyView::mouseMoveEvent(QMouseEvent *event)
 {
+    if(mbInPinch == true)return;
     QGraphicsView::mouseMoveEvent(event);
 
 //    QScrollBar * ps = verticalScrollBar();
@@ -59,8 +67,13 @@ void MyView::zoomIn()
     int centery = (psV->value() + psV->size().height()/2)/beishu;
     int centerx = (psH->value() + psH->size().width()/2)/beishu;
 
+#ifndef ANDROID
     scale(1.1, 1.1);
     beishu *= 1.1;
+#else
+    scale(1.6, 1.6);
+    beishu *= 1.6;
+#endif
  //   centerOn(450, 700 - (200 / beishu));
 
 
@@ -93,8 +106,13 @@ void MyView::zoomOut()
     int centery = (psV->value() + psV->size().height()/2)/beishu;
     int centerx = (psH->value() + psH->size().width()/2)/beishu;
 
+#ifndef ANDROID
     scale(1 / 1.1, 1 / 1.1);
     beishu /= 1.1;
+#else
+    scale(1 / 1.6, 1 / 1.6);
+    beishu /= 1.6;
+#endif
 //    centerOn(450, 700 - (200 / beishu));
 
 
@@ -135,3 +153,60 @@ void MyView::mouseDoubleClickEvent(QMouseEvent *event)
     emit dbclickxy(viewx,viewy);
     qDebug("view x is %d view y is %d ",viewx,viewy);
 }
+
+bool MyView::event(QEvent *event)
+{
+    if (event->type() == QEvent::Gesture)
+    {
+ //       qDebug("gestrue event");
+ //       return true;
+        return gestureEvent(static_cast<QGestureEvent*>(event));
+    }
+
+    return QGraphicsView::event(event);
+}
+
+bool MyView::gestureEvent(QGestureEvent *event)
+{
+    if (QGesture *pinch = event->gesture(Qt::PinchGesture))
+        pinchTriggered(static_cast<QPinchGesture *>(pinch));
+    return true;
+}
+
+void MyView::pinchTriggered(QPinchGesture *gesture)
+{
+
+    static double currentStepScaleFactor = 1;
+    static double oldfactor = 1;
+    QPinchGesture::ChangeFlags changeFlags = gesture->changeFlags();
+    if (changeFlags & QPinchGesture::ScaleFactorChanged) {
+        currentStepScaleFactor = gesture->totalScaleFactor();
+        mbInPinch = true;
+    }
+    if (gesture->state() == Qt::GestureFinished) {
+//        scaleFactor *= currentStepScaleFactor;
+//        qDebug("scale is %f ",currentStepScaleFactor);
+
+        currentStepScaleFactor = 1;
+        oldfactor = 1;
+        mbInPinch = false;
+    }
+
+    int width,hgt;
+    width = sceneRect().width();
+    hgt = sceneRect().height();
+    QScrollBar * psV = verticalScrollBar();
+    QScrollBar * psH = horizontalScrollBar();
+
+    int centery = (psV->value() + psV->size().height()/2)/beishu;
+    int centerx = (psH->value() + psH->size().width()/2)/beishu;
+
+    double fscale = currentStepScaleFactor/oldfactor;
+    scale(fscale,fscale);
+    beishu *= fscale;
+    oldfactor = currentStepScaleFactor;
+
+    centerOn(centerx,centery);
+
+}
+

+ 11 - 0
src/tool/map_lanetoxodr/myview.h

@@ -11,6 +11,9 @@
 #include <QGraphicsItem>
 #include <QKeyEvent>
 
+#include <QGestureEvent>
+#include <QPinchGesture>
+
 class MyView : public QGraphicsView
 {
     Q_OBJECT
@@ -26,6 +29,8 @@ protected:
     void mousePressEvent(QMouseEvent *event) Q_DECL_OVERRIDE;
     void mouseReleaseEvent(QMouseEvent *event) Q_DECL_OVERRIDE;
     void mouseDoubleClickEvent(QMouseEvent *event) Q_DECL_OVERRIDE;
+
+    bool event(QEvent *event) Q_DECL_OVERRIDE;
 public Q_SLOTS:
     void zoomIn();  // 放大
     void zoomOut();  // 缩小
@@ -36,6 +41,12 @@ signals:
 private:
     bool bottonstatus = false;
     QPoint myview_lastMousePos;
+
+private:
+    bool gestureEvent(QGestureEvent *event);
+    void pinchTriggered(QPinchGesture*);
+
+    bool mbInPinch = false;
 };
 
 #endif // MYVIEW_H

+ 265 - 0
src/tool/map_lanetoxodr/roaddigit.cpp

@@ -0,0 +1,265 @@
+#include "roaddigit.h"
+
+#include <math.h>
+#include "xodrfunc.h"
+
+
+RoadDigit::RoadDigit(Road * pRoad,double fspace)
+{
+    mpRoad = pRoad;
+    UpdateSpace(fspace);
+}
+
+std::vector<iv::RoadDigitUnit> * RoadDigit::GetRDU()
+{
+    return &mvectorRDU;
+}
+
+void RoadDigit::UpdateSpace(double fspace)
+{
+    if(mpRoad == 0)return;
+    CalcLine(fspace);
+    CalcLane();
+}
+
+void RoadDigit::CalcLine(double fspace)
+{
+    unsigned int j;
+    iv::RoadDigitUnit rdu;
+
+
+    bool bLastGeo = false;
+    for(j=0;j<mpRoad->GetGeometryBlockCount();j++)
+    {
+
+        GeometryBlock * pgeob = mpRoad->GetGeometryBlock(j);
+        double x,y;
+        double x_center,y_center;
+        double R;
+        RoadGeometry * pg;
+        GeometryArc * parc;
+        GeometryParamPoly3 * ppp3;
+        GeometrySpiral *pSpiral;
+        double rel_x,rel_y,rel_hdg;
+        pg = pgeob->GetGeometryAt(0);
+        x = pg->GetX();
+        y = pg->GetY();
+
+        if(j == (mpRoad->GetGeometryBlockCount() -1))
+        {
+            bLastGeo = true;
+        }
+
+        switch (pg->GetGeomType()) {
+        case 0:
+        {
+
+            rdu.mS = pg->GetS();
+            rdu.mX = pg->GetX();
+            rdu.mY = pg->GetY();
+            rdu.mfHdg = pg->GetHdg();
+            mvectorRDU.push_back(rdu);
+            int ncount = pg->GetLength() /fspace;
+            if(ncount<2)ncount = 2;
+            double fstep;
+            if(ncount > 0)fstep = pg->GetLength()/ncount;
+            int i;
+            if(bLastGeo )ncount = ncount+1;
+            for(i=1;i<ncount;i++)
+            {
+                double xtem,ytem;
+                xtem = x + (i*fstep)*cos(pg->GetHdg());
+                ytem = y + (i*fstep)*sin(pg->GetHdg());
+
+                rdu.mS = pg->GetS() + i*fstep;
+                rdu.mX = xtem;
+                rdu.mY = ytem;
+                rdu.mfHdg = pg->GetHdg();
+                mvectorRDU.push_back(rdu);
+
+            }
+        }
+            break;
+
+        case 1:
+            pSpiral = (GeometrySpiral * )pg;
+            {
+               int ncount = pSpiral->GetLength()/fspace;
+               if(ncount < 5)ncount = 5;
+               double sstep = pSpiral->GetLength()/((double)ncount);
+               int k;
+               double x0,y0,hdg0,s0;
+               x0 = pSpiral->GetX();
+               y0 = pSpiral->GetY();
+               s0 = pSpiral->GetS();
+               hdg0 = pSpiral->GetHdg() ;
+
+               rdu.mS = s0;
+               rdu.mX = x0;
+               rdu.mY = y0;
+               rdu.mfHdg = hdg0;
+               mvectorRDU.push_back(rdu);
+
+
+               pSpiral->GetCoords(s0,rel_x,rel_y,rel_hdg);
+
+               if(bLastGeo )ncount = ncount+1;
+               for(k=1;k<ncount;k++)
+               {
+                   pSpiral->GetCoords(s0+sstep*k,rel_x,rel_y,rel_hdg);
+
+                   rdu.mS = s0 + sstep * k;
+                   rdu.mX = rel_x;
+                   rdu.mY = rel_y;
+                   rdu.mfHdg = rel_hdg;
+                   mvectorRDU.push_back(rdu);
+
+            }
+        }
+
+            break;
+        case 2:
+            {
+            parc = (GeometryArc *)pg;
+            R = abs(1.0/parc->GetCurvature());
+            if(parc->GetCurvature() > 0)
+            {
+                x_center = pg->GetX() + R *cos(pg->GetHdg() + M_PI/2.0);
+                y_center = pg->GetY() + R * sin(pg->GetHdg() + M_PI/2.0);
+            }
+            else
+            {
+                x_center = pg->GetX() + R *cos(pg->GetHdg() -M_PI/2.0);
+                y_center = pg->GetY() + R * sin(pg->GetHdg() - M_PI/2.0);
+            }
+
+            rdu.mS = pg->GetS();
+            rdu.mX = pg->GetX();
+            rdu.mY = pg->GetY();
+            rdu.mfHdg = pg->GetHdg();
+            mvectorRDU.push_back(rdu);
+
+            int k;
+            int ncount = parc->GetLength() /fspace;
+            if(ncount< 5)ncount = 5;
+            double curv = parc->GetCurvature();
+            double arcrange = parc->GetLength()/R;
+            if((arcrange/0.1)>ncount)ncount = arcrange/0.1;
+            double hdgstep;
+            double hdg0 = parc->GetHdg();
+            double hdgnow = parc->GetHdg();
+            if(ncount > 0) hdgstep= (parc->GetLength()/R)/ncount;
+
+            double x_draw,y_draw;
+
+            if(curv > 0)
+            {
+                hdgnow =  hdg0 ;
+                x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
+                y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
+            }
+            else
+            {
+                hdgnow = hdg0;
+                x_draw = x_center + R *cos(hdgnow  + M_PI/2.0);
+                y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
+            }
+
+
+            if(bLastGeo )ncount = ncount+1;
+            for(k=1;k<ncount;k++)
+            {
+
+
+                if(curv > 0)
+                {
+                    hdgnow =  hdg0 + k*hdgstep;
+                    x_draw = x_center + R *cos(hdgnow - M_PI/2.0);
+                    y_draw = y_center + R * sin(hdgnow - M_PI/2.0);
+                }
+                else
+                {
+                    hdgnow = hdg0 - k * hdgstep;
+                    x_draw = x_center + R *cos(hdgnow  + M_PI/2.0);
+                    y_draw = y_center + R * sin(hdgnow + M_PI/2.0);
+                }
+
+                rdu.mS = pg->GetS() + hdgstep * k* R;
+                rdu.mX = x_draw;
+                rdu.mY = y_draw;
+                rdu.mfHdg = hdgnow;
+                mvectorRDU.push_back(rdu);
+
+
+
+            }
+            }
+            break;
+        case 4:
+            {
+            ppp3 = (GeometryParamPoly3 * )pg;
+            int ncount = ppp3->GetLength() /fspace;
+            if(ncount < 5)ncount = 5;
+            double sstep;
+            if(ncount > 0)sstep = ppp3->GetLength()/ncount;
+            else sstep = 10000.0;
+            double s = 0;
+            double xtem,ytem;
+            xtem = ppp3->GetuA() +  ppp3->GetuB() * s +  ppp3->GetuC() * s*s +  ppp3->GetuD() * s*s*s;
+            ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
+            x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
+            y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
+            s = s+ sstep;
+
+            rdu.mS = pg->GetS();
+            rdu.mX = pg->GetX();
+            rdu.mY = pg->GetY();
+            rdu.mfHdg = pg->GetHdg();
+            mvectorRDU.push_back(rdu);
+
+            double flastx = pg->GetX();
+            double flasty = pg->GetY();
+            while(s <= ppp3->GetLength())
+            {
+
+                xtem = ppp3->GetuA() +  ppp3->GetuB() * s +  ppp3->GetuC() * s*s +  ppp3->GetuD() * s*s*s;
+                ytem = ppp3->GetvA() + ppp3->GetvB() * s + ppp3->GetvC() * s*s + ppp3->GetvD() * s*s*s;
+                x = xtem*cos(ppp3->GetHdg()) - ytem * sin(ppp3->GetHdg()) + ppp3->GetX();
+                y = xtem*sin(ppp3->GetHdg()) + ytem * cos(ppp3->GetHdg()) + ppp3->GetY();
+
+                rdu.mS = pg->GetS() + s;
+                rdu.mX = x;
+                rdu.mY = y;
+                rdu.mfHdg = xodrfunc::CalcHdg(QPointF(flastx,flasty),QPointF(x,y));
+                mvectorRDU.push_back(rdu);
+
+                s = s+ sstep;
+
+
+            }
+            }
+            break;
+        default:
+            break;
+        }
+
+//         painter->drawPoint((int)(x*mnfac),(int)(y*(-1.0*mnfac)));
+
+    }
+
+}
+
+void RoadDigit::CalcLane()
+{
+    int i;
+    int ncount = mvectorRDU.size();
+    for(i=0;i<ncount;i++)
+    {
+
+        std::vector<iv::LanePoint> xvectorlp2 = xodrfunc::GetAllLanePoint(mpRoad,mvectorRDU[i].mS,
+                                                                          mvectorRDU[i].mX,mvectorRDU[i].mY,mvectorRDU[i].mfHdg);
+        mvectorRDU[i].mvectorLanePoint = xvectorlp2;
+    }
+}
+
+

+ 56 - 0
src/tool/map_lanetoxodr/roaddigit.h

@@ -0,0 +1,56 @@
+#ifndef ROADDIGIT_H
+#define ROADDIGIT_H
+
+#include "OpenDrive/OpenDrive.h"
+
+#include <vector>
+
+#include "xodrfunc.h"
+
+namespace iv {
+
+
+struct lanexy
+{
+    int nLane;
+    double mX;
+    double mY;
+    double mCenterX;
+    double mCenterY;
+    int mType = 0;
+    int mnMarkColor;
+    int mMarkType = -1;  //if -1 no mark
+    int mnChange = 0;
+    std::vector<int> mvectorsignal;
+};
+
+struct RoadDigitUnit
+{
+    double mS;
+    double mX;
+    double mY;
+    double mfHdg;
+    std::vector<iv::LanePoint> mvectorLanePoint;
+};
+
+}
+
+class RoadDigit
+{
+public:
+    RoadDigit(Road * pRoad,double fspace);
+
+private:
+    std::vector<iv::RoadDigitUnit> mvectorRDU;
+    Road * mpRoad = 0;
+
+private:
+    void CalcLine(double fspace);
+    void CalcLane();
+
+public:
+    std::vector<iv::RoadDigitUnit> * GetRDU();
+    void UpdateSpace(double fspace);
+};
+
+#endif // ROADDIGIT_H

+ 50 - 5
src/tool/map_lanetoxodr/roadeditdialog.cpp

@@ -312,6 +312,19 @@ void RoadEditDialog::on_comboBox_Road_activated(const QString &arg1)
 
 }
 
+bool RoadEditDialog::IsDrawMark(double s)
+{
+    const double dotdis = 10.0;
+    const double dotlen = 5.0;
+
+    double  y = fmod(s,dotdis);
+    if(y>dotlen)return true;
+    else
+    {
+        return false;
+    }
+}
+
 void RoadEditDialog::on_comboBox_Road_currentIndexChanged(int index)
 {
     Road * pRoad = mpxodr->GetRoad(index);
@@ -332,10 +345,18 @@ void RoadEditDialog::on_comboBox_Road_currentIndexChanged(int index)
     }
     mvectorroadview.clear();
 
+    nsize = mvectorviewitem.size();
+    for(i=0;i<nsize;i++)
+    {
+        scene->removeItem(mvectorviewitem.at(i));
+        delete mvectorviewitem.at(i);
+    }
+    mvectorviewitem.clear();
+
 
     double froad_xmin,froad_ymin,froad_xmax,froad_ymax;
     ServiceXODRTool.GetRoadMaxMin(pRoad,froad_xmin,froad_ymin,froad_xmax,froad_ymax);
-    roadviewitem * prvw = new roadviewitem(pRoad);
+//    roadviewitem * prvw = new roadviewitem(pRoad);
 
     int nfac;
     int nkeep = 30;
@@ -362,11 +383,11 @@ void RoadEditDialog::on_comboBox_Road_currentIndexChanged(int index)
     mfViewMoveX = 0 - froad_xmin - (froad_xmax - froad_xmin)/2.0;
     mfViewMoveY = 0 + froad_ymin  + (froad_ymax-froad_ymin)/2.0;
 
-    prvw->setPos(mfViewMoveX,mfViewMoveY);
+//    prvw->setPos(mfViewMoveX,mfViewMoveY);
  //       prvw->setPos((froad_xmax - froad_xmin)/2.0, (froad_ymax-froad_ymin)/2.0);
-    mvectorroadview.push_back(prvw);
-    prvw->setratio(1.0);
-    scene->addItem(prvw);
+//    mvectorroadview.push_back(prvw);
+ //   prvw->setratio(1.0);
+//    scene->addItem(prvw);
 
     mnSelGeo = -1;
 
@@ -380,6 +401,30 @@ void RoadEditDialog::on_comboBox_Road_currentIndexChanged(int index)
         ui->comboBox_Geo->addItem(QString("Geo ")+QString::number(i));
     }
 
+
+    RoadDigit xrd(mpCurRoad,0.1);
+
+    std::vector<QGraphicsPathItem *> xvectorlanepath = xodrscenfunc::GetRoadLaneItem(&xrd);
+    int j;
+    int ncount = xvectorlanepath.size();
+    for(j=0;j<ncount;j++)
+    {
+        QGraphicsPathItem * pitem = xvectorlanepath[j];
+        pitem->setPos(mfViewMoveX,mfViewMoveY);
+        scene->addItem(pitem);
+        mvectorviewitem.push_back(pitem);
+    }
+
+    std::vector<QGraphicsPathItem *> xvectormarkpath = xodrscenfunc::GetRoadMarkItem(&xrd);
+    ncount = xvectormarkpath.size();
+    for(j=0;j<ncount;j++)
+    {
+        QGraphicsPathItem * pitem = xvectormarkpath[j];
+        pitem->setPos(mfViewMoveX,mfViewMoveY);
+        scene->addItem(pitem);
+        mvectorviewitem.push_back(pitem);
+    }
+
     update();
 }
 

+ 8 - 0
src/tool/map_lanetoxodr/roadeditdialog.h

@@ -20,6 +20,9 @@
 #include "dialogroadrotate.h"
 #include "dialogroadmirror.h"
 
+#include "roaddigit.h"
+#include "xodrscenfunc.h"
+
 namespace Ui {
 class RoadEditDialog;
 }
@@ -60,6 +63,9 @@ private slots:
 
     void on_pushButton_MirrorRoad_clicked();
 
+private:
+    bool IsDrawMark(double s);
+
 private:
     Ui::RoadEditDialog *ui;
     OpenDrive * mpxodr;
@@ -76,6 +82,8 @@ private:
 
     std::vector<roadviewitem *> mvectorroadview;
 
+    std::vector<QGraphicsPathItem *> mvectorviewitem;
+
     double mfViewMoveX = 0;
     double mfViewMoveY = 0;
 };

+ 2 - 0
src/tool/map_lanetoxodr/roadviewitem.cpp

@@ -12,6 +12,8 @@ roadviewitem::roadviewitem(Road * pRoad)
 {
     mpRoad = pRoad;
     mbNeedCalc = true;
+    QGraphicsPathItem x;
+
 }
 
 QRectF roadviewitem::boundingRect() const

+ 2 - 2
src/tool/map_lanetoxodr/roadviewitem.h

@@ -101,8 +101,8 @@ private:
     bool mbShowLane = true;
     bool mbShowLine = false;
     bool mbShowRoadID = true;
-
-    bool IsDrawMark(double s);
+public:
+    static bool IsDrawMark(double s);
 };
 
 #endif // ROADVIEWITEM_H

+ 65 - 0
src/tool/map_lanetoxodr/simpleCustomEvent.cpp

@@ -0,0 +1,65 @@
+#include "simpleCustomEvent.h"
+
+#ifdef ANDROID
+#include <QFile>
+#include <QApplication>
+#include <QAndroidJniEnvironment>
+#include <QAndroidJniObject>
+#include <jni.h>
+#include "simpleCustomEvent.h"
+#include <QAndroidJniObject>
+#endif
+
+QEvent::Type SimpleCustomEvent::m_evType = (QEvent::Type)QEvent::None;
+
+SimpleCustomEvent::SimpleCustomEvent(int requestCode , int resultCode, const QVariant &msg)
+    : QEvent(eventType()), m_requestCode(requestCode), m_resultCode(resultCode),m_msg(msg)
+{}
+
+SimpleCustomEvent::~SimpleCustomEvent()
+{
+
+}
+
+QEvent::Type SimpleCustomEvent::eventType()
+{
+    if(m_evType == QEvent::None)
+    {
+        m_evType = (QEvent::Type)registerEventType();
+    }
+    return m_evType;
+}
+
+
+#ifdef ANDROID
+void onFileManager(JNIEnv *env, jobject thiz,int result, jobjectArray fileUrl);
+jclass g_extendsNative = 0;
+bool registerNativeMethods()
+{
+    JNINativeMethod methods[] {
+        {"onFileManager", "(I[Ljava/lang/String;)V", (void*)onFileManager}
+    };
+
+    const char *classname = "an/qt/extendsQtWithJava/ExtendsQtNative";
+    jclass clazz;
+    QAndroidJniEnvironment env;
+
+    QAndroidJniObject javaClass(classname);
+    clazz = env->GetObjectClass(javaClass.object<jobject>());
+    //clazz = env->FindClass(classname);
+    //qDebug() << "find ExtendsQtNative - " << clazz;
+    bool result = false;
+    if(clazz)
+    {
+        //g_extendsNative = static_cast<jclass>(env->NewGlobalRef(clazz));
+        jint ret = env->RegisterNatives(clazz,
+                                        methods,
+                                        sizeof(methods) / sizeof(methods[0]));
+        env->DeleteLocalRef(clazz);
+        //qDebug() << "RegisterNatives return - " << ret;
+        result = ret >= 0;
+    }
+    if(env->ExceptionCheck()) env->ExceptionClear();
+    return result;
+}
+#endif

+ 31 - 0
src/tool/map_lanetoxodr/simpleCustomEvent.h

@@ -0,0 +1,31 @@
+#ifndef SIMPLECUSTOMEVENT_H
+#define SIMPLECUSTOMEVENT_H
+#include <QEvent>
+#include <QString>
+#include <QVariant>
+
+//#include <QAndroidJniEnvironment>
+
+
+
+class SimpleCustomEvent : public QEvent
+{
+public:
+    SimpleCustomEvent(int requestCode = 0, int resultCode = 0, const QVariant &msg = QVariant());
+    ~SimpleCustomEvent();
+
+    static Type eventType();
+
+    int m_requestCode;
+    int m_resultCode;
+    QVariant m_msg;
+
+
+private:
+    static Type m_evType;
+};
+
+//void onFileManager(JNIEnv *env, jobject thiz,int result, jobjectArray fileUrl);
+bool registerNativeMethods();
+
+#endif // SIMPLECUSTOMEVENT_H

+ 9 - 1
src/tool/map_lanetoxodr/xodrfunc.cpp

@@ -601,6 +601,7 @@ std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double
     int nLSCount = pRoad->GetLaneSectionCount();
     double s_section = 0;
 
+
     std::vector<iv::LanePoint> xvectorlanepoint;
     for(i=0;i<nLSCount;i++)
     {
@@ -627,7 +628,7 @@ std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double
             int nlanetype = 2; //driving
             int nlanecolor = 0;
             int k;
-            double s_lane = 0;
+            double s_lane = s-s_section;
             for(k=0;k<pLane->GetLaneRoadMarkCount();k++)
             {
                  LaneRoadMark * plrm = pLane->GetLaneRoadMark(k);
@@ -638,6 +639,13 @@ std::vector<iv::LanePoint> xodrfunc::GetAllLanePoint(Road *pRoad,  const double
                          continue;
                      }
                  }
+                 else
+                 {
+                     if(s_lane<plrm->GetS())
+                     {
+                         continue;
+                     }
+                 }
                  if(plrm->GetType() == "solid")
                  {
                      nlanemarktype = 0;

+ 226 - 0
src/tool/map_lanetoxodr/xodrscenfunc.cpp

@@ -0,0 +1,226 @@
+#include "xodrscenfunc.h"
+
+xodrscenfunc::xodrscenfunc()
+{
+
+}
+
+std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadLaneItem(RoadDigit *prd)
+{
+    std::vector<QGraphicsPathItem *> xvectorgrapath;
+    std::vector<iv::RoadDigitUnit> * pvectorrdu =  prd->GetRDU();
+    int nsize = pvectorrdu->size();
+    int i;
+    for(i=0;i<(nsize-1);i++)
+    {
+        std::vector<iv::LanePoint> xvepre = pvectorrdu->at(i).mvectorLanePoint;
+        std::vector<iv::LanePoint> xvenxt = pvectorrdu->at(i+1).mvectorLanePoint;
+        if((xvepre.size()<2)||(xvenxt.size()<2)||(xvenxt.size() != xvepre.size()))
+        {
+            continue;
+        }
+        unsigned int k;
+        for(k=0;k<(xvepre.size()-1);k++)
+        {
+            QPainterPath xpath;
+            xpath.moveTo(xvepre.at(k).mfX,xvepre.at(k).mfY*(-1));
+            xpath.lineTo(xvenxt.at(k).mfX,xvenxt.at(k).mfY*(-1));
+            xpath.lineTo(xvenxt.at(k+1).mfX,xvenxt.at(k+1).mfY*(-1));
+            xpath.lineTo(xvepre.at(k+1).mfX,xvepre.at(k+1).mfY*(-1));
+            xpath.closeSubpath();
+            QGraphicsPathItem * pitem = new QGraphicsPathItem;
+            pitem->setPath(xpath);
+//            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            int nlanetype = xvepre.at(k).mnlanetype;
+            if(xvepre.at(k).mnlane<=0)nlanetype = xvepre.at(k+1).mnlanetype;
+            QColor brushcolor = Qt::darkGray;
+            switch (nlanetype) {
+            case 2:
+                brushcolor = Qt::darkGray;
+                break;
+            case 8:
+                brushcolor = Qt::red;
+                break;
+            case 9:
+                brushcolor = QColor(0xB2,0xB2,0xD6);
+                break;
+            default:
+                brushcolor = Qt::darkGreen;
+                break;
+            }
+            pitem->setBrush(brushcolor);
+            pitem->setPen(QPen(brushcolor,0.001));
+  //          mpscene->addItem(pitem);
+            xvectorgrapath.push_back(pitem);
+        }
+    }
+
+    return xvectorgrapath;
+
+
+}
+
+std::vector<QGraphicsPathItem *> xodrscenfunc::GetRoadMarkItem(RoadDigit *prd)
+{
+    std::vector<QGraphicsPathItem *> xvectorgrapath;
+    std::vector<iv::RoadDigitUnit> * pvectorrdu =  prd->GetRDU();
+    int nsize = pvectorrdu->size();
+    int i;
+    double flmw = 0.15;
+
+    for(i=0;i<(nsize-1);i++)
+    {
+        std::vector<iv::LanePoint> xvepre = pvectorrdu->at(i).mvectorLanePoint;
+        std::vector<iv::LanePoint> xvenxt = pvectorrdu->at(i+1).mvectorLanePoint;
+        if(xvenxt.size() != xvepre.size())
+        {
+            continue;
+        }
+        unsigned int k;
+        int noldmarktype = -1;
+        double foldx1,foldy1,foldx2,foldy2;
+//        double foldx1_2,foldy1_2,foldx2_2,foldy2_2;
+        double fx1,fx2,fx3,fx4,fy1,fy2,fy3,fy4;
+        for(k=0;k<(xvepre.size());k++)
+        {
+            QPainterPath xpath;
+            int ncolor = -3;
+            int nmarktype = xvepre[k].mnlanemarktype;
+            if(nmarktype >= 0)
+            {
+                if(nmarktype<2)
+                {
+                    if((nmarktype == 0)||(IsDrawMark(xvepre[k].mS)))
+                    {
+                        fx1 = xvepre[k].mfX + 0.5*flmw * cos(xvepre[k].mfhdg - M_PI/2.0);
+                        fy1 = (xvepre[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0);
+                        fx2 = xvenxt[k].mfX+ 0.5*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0);
+                        fy2 = (xvenxt[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0);
+                        fx3 = xvenxt[k].mfX + 0.5*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0);
+                        fy3 = (xvenxt[k].mfY+0.5*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0);
+                        fx4 = xvepre[k].mfX+ 0.5*flmw * cos(xvepre[k].mfhdg + M_PI/2.0);
+                        fy4 = (xvepre[k].mfY+0.5*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0);
+                        if(noldmarktype != nmarktype)
+                        {
+                        xpath.moveTo(fx1,fy1);
+                        xpath.lineTo(fx2,fy2);
+                        xpath.lineTo(fx3,fy3);
+                        xpath.lineTo(fx4,fy4);
+                        xpath.closeSubpath();
+                        }
+                        else
+                        {
+                            xpath.moveTo(foldx1,foldy1);
+                            xpath.lineTo(fx2,fy2);
+                            xpath.lineTo(fx3,fy3);
+                            xpath.lineTo(foldx2,foldy2);
+                            xpath.closeSubpath();
+                            foldx1 = fx2;
+                            foldy1 = fy2;
+                            foldx2 = fx3;
+                            foldy2 = fy3;
+                            noldmarktype = nmarktype;
+                        }
+                        ncolor = xvepre[k].mnlanecolor;
+
+
+                    }
+                }
+                else
+                {
+                    if((nmarktype == 2)||(nmarktype == 3)||(IsDrawMark(xvepre[k].mS)))
+                    {
+                        xpath.moveTo(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg + M_PI/2.0),
+                                     (xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg + M_PI/2.0),
+                                     (xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
+
+                        xpath.lineTo(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg + M_PI/2.0),
+                                     (xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg + M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg + M_PI/2.0),
+                                     (xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg + M_PI/2.0))*(-1.0));
+                        xpath.closeSubpath();
+                        ncolor = xvepre[k].mnlanecolor;
+                    }
+                    if((nmarktype == 2)||(nmarktype == 4)||(IsDrawMark(xvepre[k].mS)))
+                    {
+                        xpath.moveTo(xvepre[k].mfX + flmw * cos(xvenxt[k].mfhdg - M_PI/2.0),
+                                     (xvepre[k].mfY+flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xvenxt[k].mfX+ flmw * cos(xvepre[k].mfhdg - M_PI/2.0),
+                                     (xvenxt[k].mfY+flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
+
+                        xpath.lineTo(xvenxt[k].mfX + 2*flmw * cos(xvenxt[k].mfhdg - M_PI/2.0),
+                                     (xvenxt[k].mfY+2*flmw * sin(xvenxt[k].mfhdg - M_PI/2.0))*(-1.0));
+                        xpath.lineTo(xvepre[k].mfX+ 2*flmw * cos(xvepre[k].mfhdg - M_PI/2.0),
+                                     (xvepre[k].mfY+2*flmw * sin(xvepre[k].mfhdg - M_PI/2.0))*(-1.0));
+                        xpath.closeSubpath();
+                        ncolor = xvepre[k].mnlanecolor;
+                    }
+
+                }
+            }
+
+            if(ncolor != -3)
+            {
+                QGraphicsPathItem * pitem = new QGraphicsPathItem;
+                pitem->setPath(xpath);
+                QColor brushcolor;
+                switch (ncolor) {
+                case 0:
+                    brushcolor = Qt::white;
+                    break;
+                case 1:
+                    brushcolor = Qt::blue;
+                    break;
+                case 2:
+                    brushcolor = Qt::green;
+                    break;
+                case 3:
+                    brushcolor = Qt::red;
+                    break;
+                case 4:
+                    brushcolor = Qt::white;
+                    break;
+                case 5:
+                    brushcolor = Qt::yellow;
+                    break;
+                case 6:
+                    brushcolor = Qt::yellow; //orange use yellow replace
+                    break;
+                default:
+                    brushcolor = Qt::white;
+                    break;
+                }
+                pitem->setBrush(brushcolor);
+                pitem->setPen(QPen(brushcolor,0.001));
+//                pitem->setPos(mfViewMoveX + VIEW_WIDTH/2,-mfViewMoveY +VIEW_HEIGHT/2);
+//                mpscene->addItem(pitem);
+                xvectorgrapath.push_back(pitem);
+            }
+            else
+            {
+                noldmarktype = -1;
+            }
+
+
+        }
+
+    }
+
+    return xvectorgrapath;
+
+
+}
+
+bool xodrscenfunc::IsDrawMark(double s)
+{
+    const double dotdis = 10.0;
+    const double dotlen = 5.0;
+
+    double  y = fmod(s,dotdis);
+    if(y>dotlen)return true;
+    else
+    {
+        return false;
+    }
+}

+ 26 - 0
src/tool/map_lanetoxodr/xodrscenfunc.h

@@ -0,0 +1,26 @@
+#ifndef XODRSCENFUNC_H
+#define XODRSCENFUNC_H
+
+#include <QGraphicsScene>
+
+#include <QGraphicsPathItem>
+
+#include "xodrmake.h"
+
+#include "roaddigit.h"
+
+
+class xodrscenfunc
+{
+public:
+    xodrscenfunc();
+
+public:
+    static std::vector<QGraphicsPathItem *> GetRoadLaneItem(RoadDigit * prd);
+    static std::vector<QGraphicsPathItem *> GetRoadMarkItem(RoadDigit * prd);
+
+public:
+    static bool IsDrawMark(double s);
+};
+
+#endif // XODRSCENFUNC_H

+ 315 - 0
src/tool/map_lanetoxodr/xvmainwindow.cpp

@@ -0,0 +1,315 @@
+#include "xvmainwindow.h"
+#include "ui_xvmainwindow.h"
+
+#include <QMessageBox>
+#include <QFileDialog>
+
+#include <string.h>
+
+#include "xodrfunc.h"
+#include "roaddigit.h"
+#include "xodrscenfunc.h"
+
+#define VIEW_WIDTH 2000
+#define VIEW_HEIGHT 2000
+
+static bool IsNaN(double dat)
+{
+ qint64 & ref=*(qint64 *)&dat;
+ return (ref&0x7FF0000000000000) == 0x7FF0000000000000 && (ref&0xfffffffffffff)!=0;
+}
+
+
+XVMainWindow::XVMainWindow(QWidget *parent) :
+    QMainWindow(parent),
+    ui(new Ui::XVMainWindow)
+{
+    ui->setupUi(this);
+
+    myview = new MyView(this);
+    myview->setObjectName(QStringLiteral("graphicsView"));
+    myview->setGeometry(QRect(30, 30, 600, 600));
+
+    connect(myview,SIGNAL(dbclickxy(double,double)),this,SLOT(onClickXY(double,double)));
+
+
+    myview->setCacheMode(myview->CacheBackground);
+
+    mpscene = new  QGraphicsScene(0,0,VIEW_WIDTH,VIEW_HEIGHT);
+    mpscene->setBackgroundBrush(Qt::darkGreen);
+
+    myview->setScene(mpscene);
+
+    connect(&mFileDialog,SIGNAL(accepted()),this,SLOT(onFileOpen()));
+
+    setWindowTitle("ADC OpenDrive Viewer");
+}
+
+XVMainWindow::~XVMainWindow()
+{
+    delete ui;
+}
+
+void XVMainWindow::resizeEvent(QResizeEvent *event)
+{
+    qDebug("resize");
+    QSize sizemain = ui->centralwidget->size();
+    qDebug("size x = %d y=%d",sizemain.width(),sizemain.height());
+    myview->setGeometry(0,30,sizemain.width(),sizemain.height()-30);
+}
+
+void XVMainWindow::on_actionLoad_triggered()
+{
+
+    if(mxodr.GetRoadCount() > 0)
+    {
+        QMessageBox::StandardButton button;
+        char strquest[256];
+        snprintf(strquest,256,"Do you Want to Load New File ?");
+        button=QMessageBox::question(this,"Move",strquest,QMessageBox::Yes|QMessageBox::No);
+        if(button==QMessageBox::No)
+        {
+            return;
+        }
+        else if(button==QMessageBox::Yes)
+        {
+
+        }
+    }
+
+
+#ifndef ANDROID
+    QString strpath = QFileDialog::getOpenFileName(this,"Load XODR",".","*.xodr");
+    if(strpath.isEmpty())return;
+    LoadXODR(strpath);
+    UpdateScene();
+#else
+//    QMessageBox::warning(this,"warning","no file dialog.",QMessageBox::YesAll);
+//    QString strpath = "/storage/emulated/0/map.xodr";
+    mFileDialog.open();
+
+#endif
+
+}
+
+void XVMainWindow::LoadXODR(QString strpath)
+{
+    mxodr.Clear();
+    OpenDrive * pxodr = &mxodr;  //because add to xodr,so don't delete
+    OpenDriveXmlParser x(pxodr);
+    if(!x.ReadFile(strpath.toStdString()))
+    {
+        QMessageBox::warning(this,"warn","Can't  load xodr file.");
+        return;
+    }
+
+    int nroadnum = pxodr->GetRoadCount();
+    int i;
+    double froadlen = 0;
+    for(i=0;i<nroadnum;i++)
+    {
+        Road * pRoad = pxodr->GetRoad(i);
+        if(IsNaN(pRoad->GetRoadLength()))
+        {
+            pxodr->DeleteRoad(i);
+            i--;
+            nroadnum--;
+            qDebug("delete road %s because length is NaN",pRoad->GetRoadId().data());
+        }
+        else
+        {
+            froadlen = froadlen + pRoad->GetRoadLength();
+        }
+    }
+
+    char strout[256];
+    snprintf(strout,256,"Road count is %d. Total Len is %f",mxodr.GetRoadCount(),froadlen);
+    QMessageBox::information(this,"Info",strout,QMessageBox::YesAll);
+}
+
+void XVMainWindow::UpdateScene()
+{
+    int i;
+    int nsize = mvectorviewitem.size();
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+        delete mvectorviewitem.at(i);
+    }
+    mvectorviewitem.clear();
+
+    nsize = mxodr.GetRoadCount();
+
+    std::vector<RoadDigit> xvectorrd;
+    for(i=0;i<nsize;i++)
+    {
+        RoadDigit xrd(mxodr.GetRoad(i),10.0);
+        xvectorrd.push_back(xrd);
+    }
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectorlanepath = xodrscenfunc::GetRoadLaneItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectorlanepath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectorlanepath[j];
+            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+
+    for(i=0;i<nsize;i++)
+    {
+        std::vector<QGraphicsPathItem *> xvectormarkpath = xodrscenfunc::GetRoadMarkItem(&(xvectorrd[i]));
+        int j;
+        int ncount = xvectormarkpath.size();
+        for(j=0;j<ncount;j++)
+        {
+            QGraphicsPathItem * pitem = xvectormarkpath[j];
+            pitem->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+            mpscene->addItem(pitem);
+            mvectorviewitem.push_back(pitem);
+        }
+    }
+}
+
+
+void XVMainWindow::on_actionZoom_In_triggered()
+{
+    myview->zoomIn();
+}
+
+void XVMainWindow::on_actionZoom_Out_triggered()
+{
+    myview->zoomOut();
+}
+
+void XVMainWindow::on_actionZoom_One_triggered()
+{
+    myview->zoomone();
+}
+
+void XVMainWindow::onClickXY(double x, double y)
+{
+    double selx,sely;
+    double lon,lat;
+    selx = (x - VIEW_WIDTH/2);
+    sely = (y - VIEW_HEIGHT/2) * (-1);
+
+    mfselx = selx;
+    mfsely = sely;
+
+//    double x0,y0;
+//    GaussProjCal(glon0,glat0,&x0,&y0);
+//    GaussProjInvCal(x0+selx,y0+sely,&lon,&lat);
+
+    double rel_x,rel_y;
+    rel_x = selx - mfViewMoveX;
+    rel_y = sely - mfViewMoveY;
+
+    Road * pRoad = 0;
+    GeometryBlock * pgeob;
+    double fdis,nearx,neary,hdg;
+    double fs;
+    int nlane;
+    if(xodrfunc::GetNearPoint(rel_x,rel_y,&mxodr,&pRoad,&pgeob,fdis,nearx,neary,hdg,50,&fs,&nlane) == 0)
+    {
+        qDebug("s:%f dis is %f nlane is %d",fs,fdis,nlane);
+        char strout[1000];
+        snprintf(strout,1000,"Road:%s s:%f dis:%f nlane:%d",pRoad->GetRoadId().data(),fs,fdis,nlane);
+ //       mpLabel_Status->setText(strout);
+        ui->statusbar->showMessage(strout,10000);
+
+    }
+    else
+    {
+        char strout[1000];
+        snprintf(strout,1000,"Click x:%f y:%f",rel_x,rel_y);
+        ui->statusbar->showMessage(strout,10000);
+        qDebug("not found near road.");
+    }
+}
+
+void XVMainWindow::on_actionSet_Move_triggered()
+{
+    QMessageBox::StandardButton button;
+    char strquest[256];
+    snprintf(strquest,256,"Want to Move Center to x:%f y:%f ?",-(mfViewMoveX - mfselx),-(mfViewMoveY-mfsely));
+    button=QMessageBox::question(this,"Move",strquest,QMessageBox::Yes|QMessageBox::No);
+    if(button==QMessageBox::No)
+    {
+        return;
+    }
+    else if(button==QMessageBox::Yes)
+    {
+
+    }
+
+    mfViewMoveX = mfViewMoveX - mfselx;
+    mfViewMoveY = mfViewMoveY - mfsely;
+
+    int nsize = mvectorviewitem.size();
+    int i;
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+    }
+    for(i=0;i<nsize;i++)
+    {
+        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mpscene->addItem(mvectorviewitem.at(i));
+    }
+
+    myview->zoomIn();
+    myview->zoomOut();
+}
+
+void XVMainWindow::on_actionReset_Move_triggered()
+{
+    mfViewMoveX = 0;
+    mfViewMoveY = 0;
+    int nsize = mvectorviewitem.size();
+    int i;
+
+    for(i=0;i<nsize;i++)
+    {
+        mpscene->removeItem(mvectorviewitem.at(i));
+    }
+
+    for(i=0;i<nsize;i++)
+    {
+        mvectorviewitem.at(i)->setPos(mfViewMoveX +VIEW_WIDTH/2,-mfViewMoveY+VIEW_HEIGHT/2);
+        mpscene->addItem(mvectorviewitem.at(i));
+    }
+
+
+    myview->zoomIn();
+    myview->zoomOut();
+}
+
+void XVMainWindow::paintEvent(QPaintEvent * event)
+{
+    if(mbRefresh)
+    {
+        myview->setScene(mpscene);
+        mbRefresh = false;
+    }
+}
+
+void XVMainWindow::onFileOpen()
+{
+    QString strpath = mFileDialog.currentFile();
+    if(strpath.isEmpty())return;
+    LoadXODR(strpath);
+    UpdateScene();
+}
+
+void XVMainWindow::on_actionHelp_triggered()
+{
+    QString helpinfo = tr("Load:加载文件(后缀名为.xodr)\nZoom In:放大\nZomm Out:缩小\nZoom One:恢复默认视图\nSet Move:移动显示中心\n"
+                          "Reset Move:恢复默认显示中心\n\ntips: 在屏幕上双击选择道路(查看道路id)或者选择点(用来移动中心点 \n      "
+                          "在屏幕上可以移动查看区域");
+    QMessageBox::information(this,"Help",helpinfo,QMessageBox::Yes);
+}

+ 81 - 0
src/tool/map_lanetoxodr/xvmainwindow.h

@@ -0,0 +1,81 @@
+#ifndef XVMAINWINDOW_H
+#define XVMAINWINDOW_H
+
+#include <QMainWindow>
+
+#include "myview.h"
+
+#include <QGraphicsScene>
+
+#include "OpenDrive/OpenDrive.h"
+#include "OpenDrive/OpenDriveXmlWriter.h"
+
+#include "OpenDrive/OpenDriveXmlParser.h"
+
+#include "filedialogextern.h"
+#ifdef ANDROID
+#include "simpleCustomEvent.h"
+#endif
+
+namespace Ui {
+class XVMainWindow;
+}
+
+class XVMainWindow : public QMainWindow
+{
+    Q_OBJECT
+
+public:
+    explicit XVMainWindow(QWidget *parent = nullptr);
+    ~XVMainWindow();
+
+private slots:
+    void on_actionLoad_triggered();
+
+    void on_actionZoom_In_triggered();
+
+    void on_actionZoom_Out_triggered();
+
+    void on_actionZoom_One_triggered();
+
+    void onClickXY(double x, double y);
+
+    void on_actionSet_Move_triggered();
+
+    void on_actionReset_Move_triggered();
+
+    void onFileOpen();
+
+public:
+     void resizeEvent(QResizeEvent *event);
+
+private slots:
+    virtual void paintEvent(QPaintEvent *);
+
+     void on_actionHelp_triggered();
+
+private:
+     void LoadXODR(QString strpath);
+     void UpdateScene();
+
+private:
+    Ui::XVMainWindow *ui;
+    MyView *myview;
+    QGraphicsScene * mpscene;
+
+    std::vector<QGraphicsPathItem *> mvectorviewitem;
+
+private:
+    OpenDrive mxodr;
+    double mfViewMoveX = 0;
+    double mfViewMoveY = 0;
+
+    double mfselx = 0;
+    double mfsely = 0;
+
+    bool mbRefresh = false;
+
+    FileDialogExtern mFileDialog;
+};
+
+#endif // XVMAINWINDOW_H

+ 79 - 0
src/tool/map_lanetoxodr/xvmainwindow.ui

@@ -0,0 +1,79 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>XVMainWindow</class>
+ <widget class="QMainWindow" name="XVMainWindow">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>800</width>
+    <height>600</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>MainWindow</string>
+  </property>
+  <widget class="QWidget" name="centralwidget"/>
+  <widget class="QMenuBar" name="menubar">
+   <property name="geometry">
+    <rect>
+     <x>0</x>
+     <y>0</y>
+     <width>800</width>
+     <height>28</height>
+    </rect>
+   </property>
+   <widget class="QMenu" name="menuFile">
+    <property name="title">
+     <string>File</string>
+    </property>
+    <addaction name="actionLoad"/>
+    <addaction name="actionZoom_In"/>
+    <addaction name="actionZoom_Out"/>
+    <addaction name="actionZoom_One"/>
+    <addaction name="actionSet_Move"/>
+    <addaction name="actionReset_Move"/>
+    <addaction name="actionHelp"/>
+   </widget>
+   <addaction name="menuFile"/>
+  </widget>
+  <widget class="QStatusBar" name="statusbar"/>
+  <action name="actionLoad">
+   <property name="text">
+    <string>Load</string>
+   </property>
+  </action>
+  <action name="actionZoom_In">
+   <property name="text">
+    <string>Zoom In</string>
+   </property>
+  </action>
+  <action name="actionZoom_Out">
+   <property name="text">
+    <string>Zoom Out</string>
+   </property>
+  </action>
+  <action name="actionZoom_One">
+   <property name="text">
+    <string>Zoom One</string>
+   </property>
+  </action>
+  <action name="actionSet_Move">
+   <property name="text">
+    <string>Set Move</string>
+   </property>
+  </action>
+  <action name="actionReset_Move">
+   <property name="text">
+    <string>Reset Move</string>
+   </property>
+  </action>
+  <action name="actionHelp">
+   <property name="text">
+    <string>Help</string>
+   </property>
+  </action>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>

+ 134 - 50
src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp

@@ -231,26 +231,40 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     ServiceCarStatus.lidar_y_offset = atof(xp.GetParam("lidar_y_offset","0").data());
 
 
-
     ui->listWidget->setIconSize(QSize(40,40));
     ui->stackedWidget->setCurrentIndex(0);
 
   //  QObject::connect(ui->listWidget,SIGNAL(currentRowChanged(int)),ui->stackedWidget,SLOT(on_listWidget_clicked()));//信号与槽
     QObject::connect(ui->listWidget,SIGNAL(currentRowChanged(int)),this,SLOT(on_listWidget_clicked()));//信号与槽
 
+//    /********************************** 百度地图显示  ********************************/
+//    mMapview = new QWebEngineView(ui->stackedWidget->widget(0));
+////    qDebug((QDir::currentPath()).toLatin1().data());
+//    mMapview->load(QUrl(QString("file:///%1/%2").arg(QApplication::applicationDirPath()).arg("BaiDuMap.html")));
+//    mMapview->setGeometry(750,250,400,400);
+//    /********************************************************************************/
+
     ui->listWidget->setCurrentRow(1);    //apollo_fu debug 20200409
 
     myview = new MyView(ui->stackedWidget->widget(1));
     myview->setObjectName(QStringLiteral("graphicsView"));
     myview->setGeometry(QRect(0, 100, 900, 900)); //从屏幕上(0,100)位置开始(即为最左上角的点),显示一个900*900的界面(宽900,高900)
 
+#if 0
     myview_small = new MyView(ui->stackedWidget->widget(1));
     myview_small->setObjectName(QStringLiteral("graphicsView_small"));
     myview_small->setGeometry(QRect(1000,100,500,500));
     myview_small->setAlignment(Qt::AlignLeft | Qt::AlignTop);
+#endif
 //    myview_small->scale(0.7,0.7);
     //myview_small->centerOn(-200,-200);
 
+    /********************************** 百度地图显示  ********************************/
+    mMapview = new QWebEngineView(ui->stackedWidget->widget(1));
+//    qDebug((QDir::currentPath()).toLatin1().data());
+    mMapview->load(QUrl(QString("file:///%1/%2").arg(QApplication::applicationDirPath()).arg("BaiDuMap.html")));
+    mMapview->setGeometry(1000,100,500,500);
+    /********************************************************************************/
 
     image = new QImage(900 * 2, 900 * 2, QImage::Format_RGB32);//画布的初始化大小设为600*500,使用32位颜色
     //QImage的32、24、8位图。 图像格式:QImage::Format_RGB32 ,QImage::Format_RGB888,QImage::Format_Indexed8。
@@ -258,8 +272,9 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     image_small = new QImage(1800,1800,QImage::Format_RGB32);
 
     myview->setCacheMode(myview->CacheBackground);
+#if 0
     myview_small->setCacheMode(myview_small->CacheBackground);
-
+#endif
     painter = new QPainter(image);   //创建QPainter对象
     painter_small = new QPainter(image_small);   //创建QPainter对象
     scene = new QGraphicsScene;
@@ -291,6 +306,10 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     connect(&mTimerState,SIGNAL(timeout()),this,SLOT(onStateTimer()));//广播发送UDP数据报
     mTimerState.start(100);   //定时100ms
 
+    mTimerStateMap.setTimerType(Qt::PreciseTimer);    //
+    connect(&mTimerStateMap,SIGNAL(timeout()),this,SLOT(onStateTimerMap()));//
+    mTimerStateMap.start(500);   //定时500ms
+
     is_show_enable = true;
 
 #ifdef USE_PAD_CTRL
@@ -306,6 +325,8 @@ ADCIntelligentVehicle::ADCIntelligentVehicle(QWidget *parent)
     ModuleFun funplantrace_right = std::bind(&ADCIntelligentVehicle::UpdatePlanTrace_right,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
     mpaplantrace_right = iv::modulecomm::RegisterRecvPlus("obstraceright",funplantrace_right);
 
+    ModuleFun funfusion = std::bind(&ADCIntelligentVehicle::UpdateFusion,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
+    mpafusion = iv::modulecomm::RegisterRecvPlus("li_ra_fusion",funfusion);
 
 
     ModuleFun funmap = std::bind(&ADCIntelligentVehicle::UpdateMap,this,std::placeholders::_1,std::placeholders::_2,std::placeholders::_3,std::placeholders::_4,std::placeholders::_5);
@@ -752,6 +773,20 @@ void ADCIntelligentVehicle::onStateTimer()
     // multicast, 224.0.0.1~224.0.0.255 is multicast address of LAN
 
     //   _udp->writeDatagram(str.toUtf8(), QHostAddress("224.0.0.131"), 10002);
+
+}
+void ADCIntelligentVehicle::onStateTimerMap()
+{
+    /*******************************更新百度地图******************************/
+
+    double flat = ServiceCarStatus.location->gps_lat;
+    double flon = ServiceCarStatus.location->gps_lng;
+    double fang = ServiceCarStatus.location->ins_heading_angle;
+
+    char strscript[256];
+    snprintf(strscript,255,"theLocation(%11.7f,%11.7f,%11.7f);",flon,flat,fang);
+    mMapview->page()->runJavaScript(strscript);
+    /************************************************************************/
 }
 
 /**
@@ -922,7 +957,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         mnTimeLastUpdatePaint = mTime.elapsed();
         //       qDebug("enter paint. time is %d",mTime.elapsed());
         painter->begin(image);
-        painter_small->begin(image_small);
+//        painter_small->begin(image_small);
 
        // image->fill(QColor(60, 60, 60));//对画布进行填充
        image->fill(QColor(220, 220, 220));//对画布进行填充
@@ -954,7 +989,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
 
 
         int pointx = 450, pointy = 700;//确定坐标轴起点坐标,这里定义(35,280)
-        int pointx_small = 450, pointy_small = 700;
+//        int pointx_small = 450, pointy_small = 700;
         //        double x0[22000], y0[22000], lng[22000], x1[22000], y1[22000], x2[22000], y2[22000];
 
                 double * x0, * y0, * lng, * x1, * y1, * x2, * y2;
@@ -987,19 +1022,19 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         //先绘制车位置点及框图
         static const QPointF points1[2] = { QPointF(300, 700), QPointF(600, 700) };
         static const QPointF points2[2] = { QPointF(450, 0), QPointF(450, 900) };
-        static const QPointF points1_small[2] = { QPointF(300, 700), QPointF(600, 700) };
-        static const QPointF points2_small[2] = { QPointF(450, 0), QPointF(450, 900) };
+//        static const QPointF points1_small[2] = { QPointF(300, 700), QPointF(600, 700) };
+//        static const QPointF points2_small[2] = { QPointF(450, 0), QPointF(450, 900) };
 
         penPoint.setColor(Qt::red);
         penPoint.setWidth(2);
         painter->setPen(penPoint);
-        painter_small->setPen(penPoint);
+//        painter_small->setPen(penPoint);
         painter->drawPoint(pointx, pointy);
-        painter_small->drawPoint(pointx_small,pointy_small);
+//        painter_small->drawPoint(pointx_small,pointy_small);
         painter->drawPolyline(points1, 2);
         painter->drawPolyline(points2, 2);
-        painter_small->drawPolyline(points1_small, 2);
-        painter_small->drawPolyline(points2_small, 2);
+//        painter_small->drawPolyline(points1_small, 2);
+//        painter_small->drawPolyline(points2_small, 2);
 
         //路径点的预处理
         for (int i = 0; i < sizeN; i++)
@@ -1034,7 +1069,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         if (ServiceCarStatus.location->gps_x == 0)
         {
             painter->drawText(rect(), Qt::AlignLeft, QString::fromLocal8Bit("等待车辆实时GPS位置信息"));
-            painter_small->drawText(rect(), Qt::AlignLeft, QString::fromLocal8Bit("等待车辆实时GPS位置信息"));
+//            painter_small->drawText(rect(), Qt::AlignLeft, QString::fromLocal8Bit("等待车辆实时GPS位置信息"));
         }
         else
         {
@@ -1068,8 +1103,8 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
             #endif
         }
 
-        double kx_small = (double)(1200) / (abs(y_max - y_min));//x轴的系数
-        double ky_small = (double)(1200) / (abs(y_max - y_min));//y方向的比例系数
+//        double kx_small = (double)(1200) / (abs(y_max - y_min));//x轴的系数
+//        double ky_small = (double)(1200) / (abs(y_max - y_min));//y方向的比例系数
 
         double kx = 10;
         double ky = 10;
@@ -1085,22 +1120,22 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         for (int i = 1; i < sizeN - 1; i++)
         {
             painter->setPen(penPoint);//蓝色的笔,用于标记各个点
-            painter_small->setPen(penPoint);//蓝色的笔,用于标记各个点
+//            painter_small->setPen(penPoint);//蓝色的笔,用于标记各个点
             painter->drawPoint(pointx + x0[i] * kx, pointy - y0[i] * ky);
-            painter_small->drawPoint(pointx_small + x0[i] * kx_small, pointy_small - y0[i] * ky_small);
+//            painter_small->drawPoint(pointx_small + x0[i] * kx_small, pointy_small - y0[i] * ky_small);
             painter->drawPoint(pointx + x1[i] * kx, pointy - y1[i] * ky);
-            painter_small->drawPoint(pointx_small + x1[i] * kx_small, pointy_small - y1[i] * ky_small);
+//            painter_small->drawPoint(pointx_small + x1[i] * kx_small, pointy_small - y1[i] * ky_small);
             painter->drawPoint(pointx + x2[i] * kx, pointy - y2[i] * ky);
-            painter_small->drawPoint(pointx_small + x2[i] * kx_small, pointy_small - y2[i] * ky_small);
+//            painter_small->drawPoint(pointx_small + x2[i] * kx_small, pointy_small - y2[i] * ky_small);
         }
         painter->drawPoint(pointx + x0[sizeN - 1] * kx, pointy - y0[sizeN - 1] * ky);//绘制最后一个点
-        painter_small->drawPoint(pointx_small + x0[sizeN - 1] * kx_small, pointy_small - y0[sizeN - 1] * ky_small);//绘制最后一个点
+//        painter_small->drawPoint(pointx_small + x0[sizeN - 1] * kx_small, pointy_small - y0[sizeN - 1] * ky_small);//绘制最后一个点
 
         penPoint.setColor(Qt::red);
         penPoint.setWidth(2);
 
         painter->drawPoint(pointx + x0[0] * kx, pointy - y0[0] * ky);
-        painter_small->drawPoint(pointx_small + x0[0] * kx_small, pointy_small - y0[0] * ky_small);
+//        painter_small->drawPoint(pointx_small + x0[0] * kx_small, pointy_small - y0[0] * ky_small);
 
 #if 0
         // draw plan trace
@@ -1158,7 +1193,7 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         //pix.load("car.png");
         pix.load(":/ADCIntelligentVehicle/car1.png");
         painter->drawPixmap(435,667,30,67,pix);
-        painter_small->drawPixmap(442,683,16,34,pix);
+//        painter_small->drawPixmap(442,683,16,34,pix);
 ///////////////////////////////////////////////////////////////////
 
 
@@ -1178,56 +1213,89 @@ void ADCIntelligentVehicle::paintEvent(QPaintEvent *)
         //									//
         //////////////////////////////////////
 
-        painter->setPen(QPen(Qt::black, 2));
-        painter->setBrush(Qt::blue);
-        QFont esr_font("Microsoft YaHei", 10, 75); //第一个属性是字体(微软雅黑),第二个是大小,第三个是加粗(权重是75)
-        painter->setFont(esr_font);
-        char coordinate_ear[100];
-        iv::radar::radarobjectarray xradararray;
-        if(mbradarUpdate)
+        if(ui->checkBox_8->isChecked())
         {
-            mMutexRadar.lock();
-            xradararray.CopyFrom(mradararray);
-            mMutexRadar.unlock();
-            for (int a = 0; a < xradararray.obj_size(); a++)
+            painter->setPen(QPen(Qt::black, 2));
+            painter->setBrush(Qt::blue);
+            QFont esr_font("Microsoft YaHei", 10, 75); //第一个属性是字体(微软雅黑),第二个是大小,第三个是加粗(权重是75)
+            painter->setFont(esr_font);
+            char coordinate_ear[100];
+            iv::radar::radarobjectarray xradararray;
+            if(mbradarUpdate)
             {
-                if (xradararray.obj(a).bvalid())
+                mMutexRadar.lock();
+                xradararray.CopyFrom(mradararray);
+                mMutexRadar.unlock();
+                for (int a = 0; a < xradararray.obj_size(); a++)
                 {
-                    painter->drawEllipse(xradararray.obj(a).x() * 10 + 450, -((xradararray.obj(a).y() + ServiceCarStatus.esr_y_offset) * 10) + 700, 10, 10);
-                    sprintf(coordinate_ear, "(%d, %d)", (int)xradararray.obj(a).x(), (int)xradararray.obj(a).y());
-                    painter->drawText(xradararray.obj(a).x() * 10 + 450, -((xradararray.obj(a).y() + ServiceCarStatus.esr_y_offset ) * 10) + 700, QString(coordinate_ear));
+                    if (xradararray.obj(a).bvalid())
+                    {
+                        painter->drawEllipse(xradararray.obj(a).x() * 10 + 450, -((xradararray.obj(a).y() + ServiceCarStatus.esr_y_offset) * 10) + 700, 10, 10);
+                        sprintf(coordinate_ear, "(%d, %d)", (int)xradararray.obj(a).x(), (int)xradararray.obj(a).y());
+                        painter->drawText(xradararray.obj(a).x() * 10 + 450, -((xradararray.obj(a).y() + ServiceCarStatus.esr_y_offset ) * 10) + 700, QString(coordinate_ear));
 
+                    }
                 }
+                //           mbradarUpdate = false;
             }
-            //           mbradarUpdate = false;
         }
 
 
-        ServiceLidar.copylidarto(Lidar_read);		//激光雷达障碍物
-        ServiceLidar.copylidarobsto(Lidar_obsread);
-        painter->setPen(QColor(255, 0, 0));
-        for (unsigned int x = 0; x < Lidar_read->size(); x++)
+        if(ui->checkBox_9->isChecked())
         {
-            //painter->drawPoint(((*Lidar_read)[x].nomal_x) * 10 + 450, -(*Lidar_read)[x].nomal_y * 10 + 700);
+            ServiceLidar.copylidarto(Lidar_read);		//激光雷达障碍物
+            ServiceLidar.copylidarobsto(Lidar_obsread);
+            painter->setPen(QColor(255, 0, 0));
+            for (unsigned int x = 0; x < Lidar_read->size(); x++)
+            {
+                //painter->drawPoint(((*Lidar_read)[x].nomal_x) * 10 + 450, -(*Lidar_read)[x].nomal_y * 10 + 700);
+            }
+            painter->setPen(QColor(255,0,0));
+            for (unsigned int x = 0; x < Lidar_obsread->size(); x++)
+            {
+                painter->drawPoint(((*Lidar_obsread)[x].nomal_x) * 10 + 450, -((*Lidar_obsread)[x].nomal_y + ServiceCarStatus.lidar_y_offset) * 10 + 700);
+            }
         }
-        painter->setPen(QColor(255,0,0));
-        for (unsigned int x = 0; x < Lidar_obsread->size(); x++)
+
+
+        //////////////////////////////////////
+        //                                  //
+        //	          显示融合的信息          //
+        //									//
+        //////////////////////////////////////
+
+        if(ui->checkBox_10->isChecked())
         {
-            painter->drawPoint(((*Lidar_obsread)[x].nomal_x) * 10 + 450, -((*Lidar_obsread)[x].nomal_y + ServiceCarStatus.lidar_y_offset) * 10 + 700);
-        }
+            painter->setPen(QColor(0,255,0));
+            iv::fusion::fusionobjectarray xfusionarray;
+            if(mbfusionUpdate)
+            {
+                mMutexFusion.lock();
+                xfusionarray.CopyFrom(mfusionarray);
+                mMutexFusion.unlock();
+                for(int a = 0; a < xfusionarray.obj_size(); a++)
+                {
+                    for(int b = 0; b < xfusionarray.obj(a).nomal_centroid_size(); b++)
+                    {
+                        painter->drawPoint((xfusionarray.obj(a).nomal_centroid(b).nomal_x())*10 + 450, -(xfusionarray.obj(a).nomal_centroid(b).nomal_y())*10 + 700);
+                    }
+                }
+            }
+         }
+
 
 
 
         painter->end();
-        painter_small->end();
+//        painter_small->end();
         scene->clear();
-        scene_small->clear();
+//        scene_small->clear();
         scene->addPixmap(QPixmap::fromImage(*image));
-        scene_small->addPixmap(QPixmap::fromImage(*image_small));
+//        scene_small->addPixmap(QPixmap::fromImage(*image_small));
         myview->setScene(scene);
-        myview_small->setScene(scene_small);
+//        myview_small->setScene(scene_small);
         myview->show();
-        myview_small->show();
+//        myview_small->show();
         navigation_data.clear();
 
         if(mfSOC != 0.0)
@@ -1478,6 +1546,22 @@ void ADCIntelligentVehicle::UpdatePlanTrace_right(const char * strdata,const uns
 }
 
 
+void ADCIntelligentVehicle::UpdateFusion(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    iv::fusion::fusionobjectarray xfusionarray;
+    if(!xfusionarray.ParseFromArray(strdata,nSize))
+    {
+        gIvlog->warn("ADCIntelligentVehicle::UpdateFusion Parse Error.");
+        return;
+    }
+    mMutexFusion.lock();
+    mfusionarray.CopyFrom(xfusionarray);
+    mbfusionUpdate = true;
+    mMutexFusion.unlock();
+
+}
+
+
 /**
  * @brief ADCIntelligentVehicle::UpdateMap
  * @param strdata

+ 20 - 0
src/ui/ui_ads_hmi/ADCIntelligentVehicle.h

@@ -40,6 +40,8 @@
 
 #include <QSet>
 
+#include <QtWebEngineWidgets/QtWebEngineWidgets>
+
 #include "common/can_type.h"
 #include "common/decition_type.h"
 #include "common/vehiclestate_type.h"
@@ -64,6 +66,8 @@
 #include "ivlog.h"
 #include "mapreq.pb.h"
 #include "vbox.pb.h"
+#include "fusionobject.pb.h"
+#include "fusionobjectarray.pb.h"
 
 extern iv::Ivlog * gIvlog;
 
@@ -177,6 +181,7 @@ public slots:
 
     void onRecvUDP();
     void onStateTimer();
+    void onStateTimerMap();
     void onStateTimer1();
 protected:
 
@@ -201,8 +206,12 @@ private slots:
 
     void on_pb_v2xEn_clicked();
 
+
 private:
     Ui::ADCIntelligentVehicle *ui;
+    /**************************************/
+    QWebEngineView * mMapview;
+    /**************************************/
     //    boost::shared_ptr<iv::decition::BrainDecition> brain;
     bool is_brain_running_flag_ = false;
     bool is_map_loaded_flag_ = false;
@@ -247,6 +256,7 @@ private:
     QUdpSocket msocksend;
     QUdpSocket msockrecv;
     QTimer mTimerState;
+    QTimer mTimerStateMap;
     DataToUI mDataToUI;
 
     QTime mTime;
@@ -326,6 +336,16 @@ private:
     void * mpaplantrace_left;
     void * mpaplantrace_right;
 /**************************/
+/**********20210429***********************/
+public:
+    void UpdateFusion(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+    QMutex mMutexFusion;
+private:
+    iv::fusion::fusionobjectarray mfusionarray;
+    bool mbfusionUpdate = false;
+    void * mpafusion;
+/*****************************************/
+
 private:
     void * mpaLidar;
 

+ 49 - 1
src/ui/ui_ads_hmi/ADCIntelligentVehicle.ui

@@ -532,7 +532,7 @@
      <widget class="QGroupBox" name="groupBox_11">
       <property name="geometry">
        <rect>
-        <x>1030</x>
+        <x>1020</x>
         <y>660</y>
         <width>471</width>
         <height>201</height>
@@ -2395,6 +2395,54 @@ p, li { white-space: pre-wrap; }
      </property>
     </widget>
    </widget>
+   <widget class="QCheckBox" name="checkBox_8">
+    <property name="geometry">
+     <rect>
+      <x>1620</x>
+      <y>730</y>
+      <width>101</width>
+      <height>23</height>
+     </rect>
+    </property>
+    <property name="styleSheet">
+     <string notr="true">color: rgb(238, 238, 236);</string>
+    </property>
+    <property name="text">
+     <string>毫米波显示</string>
+    </property>
+   </widget>
+   <widget class="QCheckBox" name="checkBox_9">
+    <property name="geometry">
+     <rect>
+      <x>1620</x>
+      <y>780</y>
+      <width>101</width>
+      <height>23</height>
+     </rect>
+    </property>
+    <property name="styleSheet">
+     <string notr="true">color: rgb(238, 238, 236);</string>
+    </property>
+    <property name="text">
+     <string>激光显示</string>
+    </property>
+   </widget>
+   <widget class="QCheckBox" name="checkBox_10">
+    <property name="geometry">
+     <rect>
+      <x>1620</x>
+      <y>830</y>
+      <width>101</width>
+      <height>23</height>
+     </rect>
+    </property>
+    <property name="styleSheet">
+     <string notr="true">color: rgb(238, 238, 236);</string>
+    </property>
+    <property name="text">
+     <string>融合显示</string>
+    </property>
+   </widget>
   </widget>
   <widget class="QMenuBar" name="menuBar">
    <property name="geometry">

+ 341 - 0
src/ui/ui_ads_hmi/BaiDuMap.html

@@ -0,0 +1,341 @@
+
+
+<!DOCTYPE html>
+<html>
+<head>
+    <meta http-equiv="Content-Type" content="text/html; charset=utf-8" />
+    <meta name="viewport" content="initial-scale=1.0, user-scalable=no" />
+    <style type="text/css">
+        body, html, #allmap {
+            width: 100%;
+            height: 100%;
+            overflow: hidden;
+            margin: 0;
+            font-family: "微软雅黑";
+        }
+    </style>
+    <script type="text/javascript" src="http://api.map.baidu.com/api?v=2.0&ak=EVi8PXiYpKBGvBr7tgGMzcbdwzWWNf2o"></script>
+
+    
+    <title>野火GPS地图</title>
+</head>
+<body>
+    <div id="allmap"></div>
+
+
+
+</body>
+</html>
+
+
+
+<script type="text/javascript">
+    try {
+
+   
+    // 百度地图API功能
+    var map = new BMap.Map("allmap");            // 创建Map实例
+
+    //添加拖拽和缩放功能
+    map.enableScrollWheelZoom(true);
+    map.enableDragging();   
+
+    //添加控件和比例尺
+    var top_right_control = new BMap.ScaleControl({ anchor: BMAP_ANCHOR_BOTTOM_LEFT });// 左下角,添加比例尺
+    var top_right_navigation = new BMap.NavigationControl({ anchor: BMAP_ANCHOR_BOTTOM_LEFT });  //左下角,添加默认缩放平移控件
+
+    map.addControl(top_right_control);
+    map.addControl(top_right_navigation);
+
+
+    //添加地图类型
+    var mapType1 = new BMap.MapTypeControl({ mapTypes: [BMAP_NORMAL_MAP, BMAP_HYBRID_MAP] });
+    var mapType2 = new BMap.MapTypeControl({ anchor: BMAP_ANCHOR_TOP_LEFT });
+
+    //添加地图类型和缩略图
+   
+    map.addControl(mapType1);          //2D图,卫星图
+    map.addControl(mapType2);          //左上角,默认地图控件
+
+    var drawtrail = 0;
+
+    var grotation = 0;
+
+
+    //创建点
+    //map.clearOverlays();
+    var point = new BMap.Point(117.355, 39.066);
+    var markerCur = new BMap.Marker(point);
+    var markerObj = new BMap.Marker(point);
+    var havepointlast = 0;
+    var pointlast = new BMap.Point(116,39);
+    var pointobj = new BMap.Point(116,39);
+    var bobjset = 0;
+    var gtracelist = []; 
+    var gtraceraw = [];
+    var tracenow = 0;
+    var tracenum = 0;
+    map.centerAndZoom(point, 18);
+    var convertor = new BMap.Convertor();
+    var polylineTrace;
+/*
+    var polylineTrace =new BMap.Polyline(gtracelist, {
+    enableEditing: false,//是否启用线编辑,默认为false
+    enableClicking: false,//是否响应点击事件,默认为true
+    strokeWeight:'4',//折线的宽度,以像素为单位
+    strokeOpacity: 0.8,//折线的透明度,取值范围0 - 1
+    strokeColor:"red" //折线颜色
+    });*/
+    //var marker = new BMap.Marker(point);  // 创建标注
+    //map.addOverlay(marker);               // 将标注添加到地图中
+    
+    //根据IP定位城市
+    function myFun(result) {
+        var cityName = result.name;
+        map.setCenter(cityName);
+    }
+    var myCity = new BMap.LocalCity();
+    myCity.get(myFun);
+
+	var icon = new BMap.Icon('car.png',new BMap.Size(15,30));
+        icon.imageSize = new BMap.Size(15,30);
+        icon.anchor = new BMap.Size(8,15);
+        
+
+    //showalert(testmsg);
+
+    //对传入的经纬度进行标注:纬度,经度
+   // var Latt = 116.404;
+   // var Lott = 39.915;
+
+   // theLocation(Latt, Lott);
+   // testAlert();
+
+    function SetDrawTrail(x)
+   {
+	
+	if(x == 1)drawtrail = 1;
+	else drawtrail = 0;
+   }    
+
+
+    function clear()
+    {
+	gtracelist = [];
+    }
+
+   
+        // 用经纬度设置地图中心点
+    function objLocation(Longitude,Latitude) {
+
+        var gpsPoint = new BMap.Point(Longitude, Latitude);
+
+	var pointArr = [];
+	pointArr.push(gpsPoint);
+        convertor.translate(pointArr, 1, 5, translateCallbackobj)
+        //gps坐标纠偏
+ //       BMap.Convertor.translate(gpsPoint, 0, translateCallbackobj);     //真实经纬度转成百度坐标
+
+
+    }
+
+    // 用经纬度设置地图中心点
+    function theLocation(Longitude,Latitude,rotation) {
+        
+        grotation = rotation;
+        var gpsPoint = new BMap.Point(Longitude, Latitude);
+
+        //gps坐标纠偏
+
+
+var pointArr = [];
+pointArr.push(gpsPoint);
+        convertor.translate(pointArr, 1, 5, translateCallback)
+//convertor.translate(gpsPoint, 0, translateCallback);     //真实经纬度转成百度坐标
+ //       BMap.Convertor.translate(gpsPoint, 0, translateCallback);     //真实经纬度转成百度坐标
+
+
+            //map.clearOverlays();
+            //var new_point = new BMap.Point(Longitude,Latitude );
+            //var marker = new BMap.Marker(new_point);  // 创建标注
+            //map.addOverlay(marker);              // 将标注添加到地图中
+            //map.panTo(new_point);
+            //marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+
+    }
+
+
+function settrace(numlist,num2list)                    //仅把qt传来的数组转换成可用的list
+{
+    //alert(numlist);
+    var num_list,num2_list;                         //以下为格式转换,分割成可用的数组
+    num_list = numlist.substring(1,numlist.length-1);
+    num2_list = num2list.substring(1,num2list.length-1);
+    num_list = num_list.split(",");
+    num2_list = num2_list.split(",");
+    //alert("the num_list is: "+num_list[0]+" "+num_list[1]);
+
+    
+    gtraceraw = [];
+    gtracelist = [];
+    for(i=0;i<num_list.length;i++)
+    {
+        point= new BMap.Point(num_list[i],num2_list[i]);
+        gtraceraw.push(point);                                  
+    }
+    tracenum = num_list.length;
+    tracenow = 0;
+
+    setTimeout("converttrace()", 30);// 调用画轨迹的函数
+
+    
+}
+
+function converttrace() 
+{
+    var tracelist = [];     //为轨迹做准备,把所有的点扔里面,但不对每个点标注
+    var index = 0;
+    for(i=tracenow;i<tracenum;i++)
+    {
+	tracelist.push(gtraceraw[i]);
+	index++;
+	if(index>=10)break;
+    }
+    if(index>0)
+    {
+	
+        convertor.translate(tracelist, 1,5,translateCallbacktrace);     //真实经纬度转成百度坐标
+     }
+
+}
+
+
+translateCallbacktrace = function (data){
+      if(data.status == 0) {
+        for (var i = 0; i < data.points.length; i++) {
+	gtracelist.push(data.points[i]);
+        }
+	tracenow = tracenow + data.points.length;
+      }
+
+    map.removeOverlay(polylineTrace);
+    polylineTrace =new BMap.Polyline(gtracelist, {
+    enableEditing: false,//是否启用线编辑,默认为false
+    enableClicking: false,//是否响应点击事件,默认为true
+    strokeWeight:'4',//折线的宽度,以像素为单位
+    strokeOpacity: 0.8,//折线的透明度,取值范围0 - 1
+    strokeColor:"red" //折线颜色
+    });
+    map.addOverlay(polylineTrace);          //增加折线
+      setTimeout("converttrace()", 250);// 调用画轨迹的函数
+	
+}
+
+
+
+
+    // 用经纬度设置地图中心点
+    function testAlert(msg) {
+
+        var str = new String;
+        str =  msg.toString()
+       // str = "test"
+
+        alert(str);
+    }
+
+    function enableZoomDrag()
+    {
+        //添加拖拽和缩放功能
+        map.enableScrollWheelZoom(true);
+        map.enableDragging();
+    }
+
+        //坐标转换完之后的回调函数
+    translateCallbackmap = function (point) {
+
+	gtracelist.push(point);       
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+        //坐标转换完之后的回调函数
+    translateCallbacktr = function (point) {
+
+	gtracelist.push(point);       
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+    //坐标转换完之后的回调函数
+    translateCallbackobj = function (data) {
+	if(data.status === 0) {
+         var point = data.points[0];
+	pointobj = point;
+	bobjset = 1;
+ //       map.clearOverlays();
+	map.removeOverlay(markerObj);
+        markerObj = new BMap.Marker(point);
+
+        map.addOverlay(markerObj);
+	}
+
+ //       map.setCenter(point);
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+
+    //坐标转换完之后的回调函数
+    translateCallback = function (data) {
+
+if(data.status === 0) {
+         var point = data.points[0]
+        map.removeOverlay(markerCur);
+        markerCur = new BMap.Marker(point);
+        if(havepointlast == 1)
+	{
+		if(drawtrail == 1)
+		{
+		var line = new BMap.Polyline([pointlast, point], {strokeColor: "green", strokeWeight: 1, strokeOpacity: 1});
+		map.addOverlay(line);  
+		line.disableMassClear();
+		}
+	}
+        pointlast = point;
+        havepointlast = 1;
+
+	markerCur.setOffset(-30,-30);
+	markerCur.setIcon(icon); 
+	markerCur.setShadow(icon) 
+	markerCur.setRotation(grotation);
+        map.addOverlay(markerCur);
+        map.setCenter(point);
+      }
+//	return;
+//        map.clearOverlays();
+
+/*
+	if(bobjset == 1)
+	{
+		map.removeOverlay(markerObj);
+        	markerObj = new BMap.Marker(pointobj);
+
+        	map.addOverlay(markerObj);
+	}
+
+*/
+
+      //  marker.setAnimation(BMAP_ANIMATION_BOUNCE); //跳动的动画
+    }
+
+    } catch (e) {
+
+        alert("地图加载失败,请检查网络!");
+
+    }
+
+   
+</script>
+
+
+

+ 7 - 3
src/ui/ui_ads_hmi/ui_ads_hmi.pro

@@ -4,7 +4,7 @@
 #
 #-------------------------------------------------
 
-QT       += core gui network
+QT       += core gui network webenginewidgets
 
 greaterThan(QT_MAJOR_VERSION, 4): QT += widgets
 
@@ -52,7 +52,9 @@ SOURCES += \
     ../../include/msgtype/v2x.pb.cc \
     ../../include/msgtype/chassis.pb.cc \
     ../../include/msgtype/mapreq.pb.cc  \
-    ../../include/msgtype/vbox.pb.cc
+    ../../include/msgtype/vbox.pb.cc \
+    ../../include/msgtype/fusionobjectarray.pb.cc \
+    ../../include/msgtype/fusionobject.pb.cc
 
 HEADERS += \
         ADCIntelligentVehicle.h \
@@ -71,7 +73,9 @@ HEADERS += \
     ../../include/msgtype/v2x.pb.h \
     ../../include/msgtype/chassis.pb.h \
     ../../include/msgtype/mapreq.pb.h \
-    ../../include/msgtype/vbox.pb.h
+    ../../include/msgtype/vbox.pb.h \
+    ../../include/msgtype/fusionobjectarray.pb.h \
+    ../../include/msgtype/fusionobject.pb.h
 
 
 FORMS += \

+ 73 - 0
src1/common/modulecomm/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 152 - 0
src1/common/modulecomm/modulecomm.cpp

@@ -0,0 +1,152 @@
+#include "modulecomm.h"
+#include <iostream>
+
+namespace iv {
+namespace modulecomm {
+
+struct ModeduleInfo
+{
+    void * mphandle;
+    ModuleComm_TYPE mmctype;
+};
+
+void *  RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount,
+                     ModuleComm_TYPE xmctype)
+{
+
+    iv::modulecomm::ModeduleInfo * pmi = new iv::modulecomm::ModeduleInfo;
+    pmi->mmctype = xmctype;
+    pmi->mphandle = 0;
+    switch (xmctype) {
+    case ModuleComm_SHAREMEM:
+        pmi->mphandle = iv::modulecomm_shm::RegisterSend(strcommname,nBufSize,nMsgBufCount);
+        break;
+    case ModuleComm_FASTRTPS:
+        pmi->mphandle = iv::modulecomm_fastrtps::RegisterSend(strcommname,nBufSize,nMsgBufCount);
+        break;
+    case ModuleComm_INTERIOR:
+        pmi->mphandle = iv::modulecomm_inter::RegisterSend(strcommname,nBufSize,nMsgBufCount);
+        break;
+    default:
+        break;
+    }
+    return pmi;
+}
+
+void  *  RegisterRecv(const char * strcommname,SMCallBack pCall,ModuleComm_TYPE xmctype)
+{
+    iv::modulecomm::ModeduleInfo * pmi = new iv::modulecomm::ModeduleInfo;
+    pmi->mmctype = xmctype;
+    pmi->mphandle = 0;
+    switch (xmctype) {
+    case ModuleComm_SHAREMEM:
+        pmi->mphandle = iv::modulecomm_shm::RegisterRecv(strcommname,pCall);
+        break;
+    case ModuleComm_FASTRTPS:
+        pmi->mphandle = iv::modulecomm_fastrtps::RegisterRecv(strcommname,pCall);
+        break;
+    case ModuleComm_INTERIOR:
+        pmi->mphandle = iv::modulecomm_inter::RegisterRecv(strcommname,pCall);
+        break;
+    default:
+        break;
+    }
+    return pmi;
+}
+
+void *  RegisterRecvPlus(const char * strcommname,ModuleFun xFun,
+                                                ModuleComm_TYPE xmctype)
+{
+    iv::modulecomm::ModeduleInfo * pmi = new iv::modulecomm::ModeduleInfo;
+    pmi->mmctype = xmctype;
+    pmi->mphandle = 0;
+    switch (xmctype) {
+    case ModuleComm_SHAREMEM:
+        pmi->mphandle = iv::modulecomm_shm::RegisterRecvPlus(strcommname,xFun);
+        break;
+    case ModuleComm_FASTRTPS:
+        pmi->mphandle = iv::modulecomm_fastrtps::RegisterRecvPlus(strcommname,xFun);
+        break;
+    case ModuleComm_INTERIOR:
+        pmi->mphandle = iv::modulecomm_inter::RegisterRecvPlus(strcommname,xFun);
+        break;
+    default:
+        break;
+    }
+    return pmi;
+}
+
+void  ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen)
+{
+    iv::modulecomm::ModeduleInfo * pmi = (iv::modulecomm::ModeduleInfo  * )pHandle;
+    switch (pmi->mmctype) {
+    case ModuleComm_SHAREMEM:
+        iv::modulecomm_shm::ModuleSendMsg(pmi->mphandle,strdata,nDataLen);
+        break;
+    case ModuleComm_FASTRTPS:
+        iv::modulecomm_fastrtps::ModuleSendMsg(pmi->mphandle,strdata,nDataLen);
+        break;
+    case ModuleComm_INTERIOR:
+        iv::modulecomm_inter::ModuleSendMsg(pmi->mphandle,strdata,nDataLen);
+        break;
+    default:
+        break;
+    }
+}
+
+void  Unregister(void * pHandle)
+{
+    iv::modulecomm::ModeduleInfo * pmi = (iv::modulecomm::ModeduleInfo  * )pHandle;
+    switch (pmi->mmctype) {
+    case ModuleComm_SHAREMEM:
+        iv::modulecomm_shm::Unregister(pmi->mphandle);
+        break;
+    case ModuleComm_FASTRTPS:
+        iv::modulecomm_fastrtps::Unregister(pmi->mphandle);
+        break;
+    case ModuleComm_INTERIOR:
+        iv::modulecomm_inter::Unregister(pmi->mphandle);
+        break;
+    default:
+        break;
+    }
+}
+
+void PauseComm(void *pHandle)
+{
+    iv::modulecomm::ModeduleInfo * pmi = (iv::modulecomm::ModeduleInfo  * )pHandle;
+    switch (pmi->mmctype) {
+    case ModuleComm_SHAREMEM:
+        iv::modulecomm_shm::PauseComm(pmi->mphandle);
+        break;
+    case ModuleComm_FASTRTPS:
+        iv::modulecomm_fastrtps::PauseComm(pmi->mphandle);
+        break;
+    case ModuleComm_INTERIOR:
+        iv::modulecomm_inter::PauseComm(pmi->mphandle);
+        break;
+    default:
+        break;
+    }
+}
+
+void ContintuComm(void *pHandle)
+{
+    iv::modulecomm::ModeduleInfo * pmi = (iv::modulecomm::ModeduleInfo  * )pHandle;
+    switch (pmi->mmctype) {
+    case ModuleComm_SHAREMEM:
+        iv::modulecomm_shm::ContintuComm(pmi->mphandle);
+        break;
+    case ModuleComm_FASTRTPS:
+        iv::modulecomm_fastrtps::ContintuComm(pmi->mphandle);
+        break;
+    case ModuleComm_INTERIOR:
+        iv::modulecomm_inter::ContintuComm(pmi->mphandle);
+        break;
+    default:
+        break;
+    }
+}
+
+}
+}

+ 64 - 0
src1/common/modulecomm/modulecomm.h

@@ -0,0 +1,64 @@
+#ifndef MODULECOMM_H
+#define MODULECOMM_H
+
+
+#include <QtCore/qglobal.h>
+#include <QDateTime>
+
+#include <functional>
+
+
+#include "modulecomm_shm.h"
+#include "modulecomm_fastrtps.h"
+#include "modulecomm_inter.h"
+
+#if defined(MODULECOMM_LIBRARY)
+#  define MODULECOMMSHARED_EXPORT Q_DECL_EXPORT
+#else
+#  define MODULECOMMSHARED_EXPORT Q_DECL_IMPORT
+#endif
+
+
+
+
+
+
+//#include <iostream>
+//#include <thread>
+
+//using namespace std::placeholders;
+
+#ifndef IV_MODULE_FUN
+
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+#define IV_MODULE_FUN
+#endif
+
+namespace iv {
+namespace modulecomm {
+
+enum ModuleComm_TYPE
+{
+    ModuleComm_SHAREMEM = 0,
+    ModuleComm_INTERIOR = 1,
+    ModuleComm_FASTRTPS = 2
+};
+
+
+void * MODULECOMMSHARED_EXPORT RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount
+                                            ,ModuleComm_TYPE xmctype = ModuleComm_SHAREMEM);
+void * MODULECOMMSHARED_EXPORT RegisterRecv(const char * strcommname,SMCallBack pCall,
+                                            ModuleComm_TYPE xmctype = ModuleComm_SHAREMEM);
+void * MODULECOMMSHARED_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun,
+                                                ModuleComm_TYPE xmctype = ModuleComm_SHAREMEM);
+void MODULECOMMSHARED_EXPORT ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen);
+void MODULECOMMSHARED_EXPORT Unregister(void * pHandle);
+void MODULECOMMSHARED_EXPORT PauseComm(void * pHandle);
+void MODULECOMMSHARED_EXPORT ContintuComm(void * pHandle);
+
+}
+
+}
+
+#endif // MODULECOMM_H

+ 36 - 0
src1/common/modulecomm/modulecomm.pro

@@ -0,0 +1,36 @@
+QT -= gui
+
+TEMPLATE = lib
+DEFINES += MODULECOMM_LIBRARY
+
+CONFIG += c++11
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+    modulecomm.cpp
+
+HEADERS += \
+    modulecomm.h
+
+CONFIG += plugin
+
+# Default rules for deployment.
+unix {
+    target.path = /usr/lib
+}
+!isEmpty(target.path): INSTALLS += target
+
+
+INCLUDEPATH += $$PWD/../modulecomm_shm
+INCLUDEPATH += $$PWD/../modulecomm_fastrtps
+INCLUDEPATH += $$PWD/../modulecomm_inter

+ 323 - 0
src1/common/modulecomm_fastrtps/Topics.cxx

@@ -0,0 +1,323 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file Topics.cpp
+ * This source file contains the definition of the described types in the IDL file.
+ *
+ * This file was generated by the tool gen.
+ */
+
+#ifdef _WIN32
+// Remove linker warning LNK4221 on Visual Studio
+namespace { char dummy; }
+#endif
+
+#include "Topics.h"
+#include <fastcdr/Cdr.h>
+
+#include <fastcdr/exceptions/BadParamException.h>
+using namespace eprosima::fastcdr::exception;
+
+#include <utility>
+
+
+TopicSample::Message::Message()
+{
+    // m_msgname com.eprosima.idl.parser.typecode.StringTypeCode@76329302
+    m_msgname ="";
+    // m_counter com.eprosima.idl.parser.typecode.PrimitiveTypeCode@5e25a92e
+    m_counter = 0;
+    // m_sendtime com.eprosima.idl.parser.typecode.PrimitiveTypeCode@4df828d7
+    m_sendtime = 0;
+    // m_xdata com.eprosima.idl.parser.typecode.AliasTypeCode@b59d31
+
+    m_xdata.push_back(1);
+    m_xdata.push_back(2);
+
+
+}
+
+TopicSample::Message::~Message()
+{
+
+
+
+
+}
+
+TopicSample::Message::Message(const Message &x)
+{
+    m_msgname = x.m_msgname;
+    m_counter = x.m_counter;
+    m_sendtime = x.m_sendtime;
+    m_xdata = x.m_xdata;
+}
+
+TopicSample::Message::Message(Message &&x)
+{
+    m_msgname = std::move(x.m_msgname);
+    m_counter = x.m_counter;
+    m_sendtime = x.m_sendtime;
+    m_xdata = std::move(x.m_xdata);
+}
+
+TopicSample::Message& TopicSample::Message::operator=(const Message &x)
+{
+
+    m_msgname = x.m_msgname;
+    m_counter = x.m_counter;
+    m_sendtime = x.m_sendtime;
+    m_xdata = x.m_xdata;
+
+    return *this;
+}
+
+TopicSample::Message& TopicSample::Message::operator=(Message &&x)
+{
+
+    m_msgname = std::move(x.m_msgname);
+    m_counter = x.m_counter;
+    m_sendtime = x.m_sendtime;
+    m_xdata = std::move(x.m_xdata);
+
+    return *this;
+}
+
+size_t TopicSample::Message::getMaxCdrSerializedSize(size_t current_alignment)
+{
+    size_t initial_alignment = current_alignment;
+
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + 255 + 1;
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
+
+
+    current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8);
+
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
+
+    current_alignment += (100 * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1);
+
+
+
+    return 10000000;
+//    return current_alignment - initial_alignment;
+}
+
+size_t TopicSample::Message::getCdrSerializedSize(const TopicSample::Message& data, size_t current_alignment)
+{
+    (void)data;
+    size_t initial_alignment = current_alignment;
+
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4) + data.msgname().size() + 1;
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
+
+
+    current_alignment += 8 + eprosima::fastcdr::Cdr::alignment(current_alignment, 8);
+
+
+    current_alignment += 4 + eprosima::fastcdr::Cdr::alignment(current_alignment, 4);
+
+    if (data.xdata().size() > 0)
+    {
+        current_alignment += (data.xdata().size() * 1) + eprosima::fastcdr::Cdr::alignment(current_alignment, 1);
+    }
+
+
+
+
+    return current_alignment - initial_alignment;
+}
+
+void TopicSample::Message::serialize(eprosima::fastcdr::Cdr &scdr) const
+{
+
+    scdr << m_msgname;
+    scdr << m_counter;
+    scdr << m_sendtime;
+    scdr << m_xdata;
+
+//    std::cout<<"serialize."<<std::endl;
+}
+
+void TopicSample::Message::deserialize(eprosima::fastcdr::Cdr &dcdr)
+{
+
+    dcdr >> m_msgname;
+    dcdr >> m_counter;
+    dcdr >> m_sendtime;
+    dcdr >> m_xdata;
+}
+
+/*!
+ * @brief This function copies the value in member msgname
+ * @param _msgname New value to be copied in member msgname
+ */
+void TopicSample::Message::msgname(const std::string &_msgname)
+{
+m_msgname = _msgname;
+}
+
+/*!
+ * @brief This function moves the value in member msgname
+ * @param _msgname New value to be moved in member msgname
+ */
+void TopicSample::Message::msgname(std::string &&_msgname)
+{
+m_msgname = std::move(_msgname);
+}
+
+/*!
+ * @brief This function returns a constant reference to member msgname
+ * @return Constant reference to member msgname
+ */
+const std::string& TopicSample::Message::msgname() const
+{
+    return m_msgname;
+}
+
+/*!
+ * @brief This function returns a reference to member msgname
+ * @return Reference to member msgname
+ */
+std::string& TopicSample::Message::msgname()
+{
+    return m_msgname;
+}
+/*!
+ * @brief This function sets a value in member counter
+ * @param _counter New value for member counter
+ */
+void TopicSample::Message::counter(int32_t _counter)
+{
+m_counter = _counter;
+}
+
+/*!
+ * @brief This function returns the value of member counter
+ * @return Value of member counter
+ */
+int32_t TopicSample::Message::counter() const
+{
+    return m_counter;
+}
+
+/*!
+ * @brief This function returns a reference to member counter
+ * @return Reference to member counter
+ */
+int32_t& TopicSample::Message::counter()
+{
+    return m_counter;
+}
+
+/*!
+ * @brief This function sets a value in member sendtime
+ * @param _sendtime New value for member sendtime
+ */
+void TopicSample::Message::sendtime(int64_t _sendtime)
+{
+m_sendtime = _sendtime;
+}
+
+/*!
+ * @brief This function returns the value of member sendtime
+ * @return Value of member sendtime
+ */
+int64_t TopicSample::Message::sendtime() const
+{
+    return m_sendtime;
+}
+
+/*!
+ * @brief This function returns a reference to member sendtime
+ * @return Reference to member sendtime
+ */
+int64_t& TopicSample::Message::sendtime()
+{
+    return m_sendtime;
+}
+
+/*!
+ * @brief This function copies the value in member xdata
+ * @param _xdata New value to be copied in member xdata
+ */
+void TopicSample::Message::xdata(const TopicSample::SomeBytes &_xdata)
+{
+ //   return;
+  m_xdata = _xdata;
+//int i;
+//for(i=0;i<300;i++)
+//    m_xdata.push_back(_xdata.at(i));
+}
+
+/*!
+ * @brief This function moves the value in member xdata
+ * @param _xdata New value to be moved in member xdata
+ */
+void TopicSample::Message::xdata(TopicSample::SomeBytes &&_xdata)
+{
+m_xdata = std::move(_xdata);
+}
+
+/*!
+ * @brief This function returns a constant reference to member xdata
+ * @return Constant reference to member xdata
+ */
+const TopicSample::SomeBytes& TopicSample::Message::xdata() const
+{
+    return m_xdata;
+}
+
+/*!
+ * @brief This function returns a reference to member xdata
+ * @return Reference to member xdata
+ */
+TopicSample::SomeBytes& TopicSample::Message::xdata()
+{
+    return m_xdata;
+}
+
+size_t TopicSample::Message::getKeyMaxCdrSerializedSize(size_t current_alignment)
+{
+    size_t current_align = current_alignment;
+
+
+
+
+
+
+
+    return current_align;
+}
+
+bool TopicSample::Message::isKeyDefined()
+{
+   return false;
+}
+
+void TopicSample::Message::serializeKey(eprosima::fastcdr::Cdr &scdr) const
+{
+    (void) scdr;
+     
+     
+     
+     
+}
+

+ 253 - 0
src1/common/modulecomm_fastrtps/Topics.h

@@ -0,0 +1,253 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file Topics.h
+ * This header file contains the declaration of the described types in the IDL file.
+ *
+ * This file was generated by the tool gen.
+ */
+
+#ifndef _TOPICSAMPLE_TOPICS_H_
+#define _TOPICSAMPLE_TOPICS_H_
+
+// TODO Poner en el contexto.
+
+#include <stdint.h>
+#include <array>
+#include <string>
+#include <vector>
+#include <map>
+#include <bitset>
+
+#if defined(_WIN32)
+#if defined(EPROSIMA_USER_DLL_EXPORT)
+#define eProsima_user_DllExport __declspec( dllexport )
+#else
+#define eProsima_user_DllExport
+#endif
+#else
+#define eProsima_user_DllExport
+#endif
+
+#if defined(_WIN32)
+#if defined(EPROSIMA_USER_DLL_EXPORT)
+#if defined(Topics_SOURCE)
+#define Topics_DllAPI __declspec( dllexport )
+#else
+#define Topics_DllAPI __declspec( dllimport )
+#endif // Topics_SOURCE
+#else
+#define Topics_DllAPI
+#endif
+#else
+#define Topics_DllAPI
+#endif // _WIN32
+
+namespace eprosima
+{
+    namespace fastcdr
+    {
+        class Cdr;
+    }
+}
+
+
+namespace TopicSample
+{
+    typedef std::vector<uint8_t> SomeBytes;
+    /*!
+     * @brief This class represents the structure Message defined by the user in the IDL file.
+     * @ingroup TOPICS
+     */
+    class Message
+    {
+    public:
+
+        /*!
+         * @brief Default constructor.
+         */
+        eProsima_user_DllExport Message();
+
+        /*!
+         * @brief Default destructor.
+         */
+        eProsima_user_DllExport ~Message();
+
+        /*!
+         * @brief Copy constructor.
+         * @param x Reference to the object TopicSample::Message that will be copied.
+         */
+        eProsima_user_DllExport Message(const Message &x);
+
+        /*!
+         * @brief Move constructor.
+         * @param x Reference to the object TopicSample::Message that will be copied.
+         */
+        eProsima_user_DllExport Message(Message &&x);
+
+        /*!
+         * @brief Copy assignment.
+         * @param x Reference to the object TopicSample::Message that will be copied.
+         */
+        eProsima_user_DllExport Message& operator=(const Message &x);
+
+        /*!
+         * @brief Move assignment.
+         * @param x Reference to the object TopicSample::Message that will be copied.
+         */
+        eProsima_user_DllExport Message& operator=(Message &&x);
+
+        /*!
+         * @brief This function copies the value in member msgname
+         * @param _msgname New value to be copied in member msgname
+         */
+        eProsima_user_DllExport void msgname(const std::string &_msgname);
+
+        /*!
+         * @brief This function moves the value in member msgname
+         * @param _msgname New value to be moved in member msgname
+         */
+        eProsima_user_DllExport void msgname(std::string &&_msgname);
+
+        /*!
+         * @brief This function returns a constant reference to member msgname
+         * @return Constant reference to member msgname
+         */
+        eProsima_user_DllExport const std::string& msgname() const;
+
+        /*!
+         * @brief This function returns a reference to member msgname
+         * @return Reference to member msgname
+         */
+        eProsima_user_DllExport std::string& msgname();
+        /*!
+         * @brief This function sets a value in member counter
+         * @param _counter New value for member counter
+         */
+        eProsima_user_DllExport void counter(int32_t _counter);
+
+        /*!
+         * @brief This function returns the value of member counter
+         * @return Value of member counter
+         */
+        eProsima_user_DllExport int32_t counter() const;
+
+        /*!
+         * @brief This function returns a reference to member counter
+         * @return Reference to member counter
+         */
+        eProsima_user_DllExport int32_t& counter();
+
+        /*!
+         * @brief This function sets a value in member sendtime
+         * @param _sendtime New value for member sendtime
+         */
+        eProsima_user_DllExport void sendtime(int64_t _sendtime);
+
+        /*!
+         * @brief This function returns the value of member sendtime
+         * @return Value of member sendtime
+         */
+        eProsima_user_DllExport int64_t sendtime() const;
+
+        /*!
+         * @brief This function returns a reference to member sendtime
+         * @return Reference to member sendtime
+         */
+        eProsima_user_DllExport int64_t& sendtime();
+
+        /*!
+         * @brief This function copies the value in member xdata
+         * @param _xdata New value to be copied in member xdata
+         */
+        eProsima_user_DllExport void xdata(const TopicSample::SomeBytes &_xdata);
+
+        /*!
+         * @brief This function moves the value in member xdata
+         * @param _xdata New value to be moved in member xdata
+         */
+        eProsima_user_DllExport void xdata(TopicSample::SomeBytes &&_xdata);
+
+        /*!
+         * @brief This function returns a constant reference to member xdata
+         * @return Constant reference to member xdata
+         */
+        eProsima_user_DllExport const TopicSample::SomeBytes& xdata() const;
+
+        /*!
+         * @brief This function returns a reference to member xdata
+         * @return Reference to member xdata
+         */
+        eProsima_user_DllExport TopicSample::SomeBytes& xdata();
+
+        /*!
+         * @brief This function returns the maximum serialized size of an object
+         * depending on the buffer alignment.
+         * @param current_alignment Buffer alignment.
+         * @return Maximum serialized size.
+         */
+        eProsima_user_DllExport static size_t getMaxCdrSerializedSize(size_t current_alignment = 0);
+
+        /*!
+         * @brief This function returns the serialized size of a data depending on the buffer alignment.
+         * @param data Data which is calculated its serialized size.
+         * @param current_alignment Buffer alignment.
+         * @return Serialized size.
+         */
+        eProsima_user_DllExport static size_t getCdrSerializedSize(const TopicSample::Message& data, size_t current_alignment = 0);
+
+
+        /*!
+         * @brief This function serializes an object using CDR serialization.
+         * @param cdr CDR serialization object.
+         */
+        eProsima_user_DllExport void serialize(eprosima::fastcdr::Cdr &cdr) const;
+
+        /*!
+         * @brief This function deserializes an object using CDR serialization.
+         * @param cdr CDR serialization object.
+         */
+        eProsima_user_DllExport void deserialize(eprosima::fastcdr::Cdr &cdr);
+
+
+
+        /*!
+         * @brief This function returns the maximum serialized size of the Key of an object
+         * depending on the buffer alignment.
+         * @param current_alignment Buffer alignment.
+         * @return Maximum serialized size.
+         */
+        eProsima_user_DllExport static size_t getKeyMaxCdrSerializedSize(size_t current_alignment = 0);
+
+        /*!
+         * @brief This function tells you if the Key has been defined for this type
+         */
+        eProsima_user_DllExport static bool isKeyDefined();
+
+        /*!
+         * @brief This function serializes the key members of an object using CDR serialization.
+         * @param cdr CDR serialization object.
+         */
+        eProsima_user_DllExport void serializeKey(eprosima::fastcdr::Cdr &cdr) const;
+
+    private:
+        std::string m_msgname;
+        int32_t m_counter;
+        int64_t m_sendtime;
+        TopicSample::SomeBytes m_xdata;
+    };
+}
+
+#endif // _TOPICSAMPLE_TOPICS_H_

+ 13 - 0
src1/common/modulecomm_fastrtps/Topics.idl

@@ -0,0 +1,13 @@
+module TopicSample {
+
+#pragma DCPS_DATA_TYPE "TopicSample::Message"
+
+typedef sequence<octet> SomeBytes;
+struct Message {
+  string msgname;
+  long counter;
+  long long sendtime;
+  SomeBytes   xdata;
+};
+
+};

+ 138 - 0
src1/common/modulecomm_fastrtps/TopicsPubSubTypes.cxx

@@ -0,0 +1,138 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsPubSubTypes.cpp
+ * This header file contains the implementation of the serialization functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+
+#include <fastcdr/FastBuffer.h>
+#include <fastcdr/Cdr.h>
+
+#include "TopicsPubSubTypes.h"
+
+using namespace eprosima::fastrtps;
+using namespace eprosima::fastrtps::rtps;
+
+namespace TopicSample
+{
+
+    MessagePubSubType::MessagePubSubType()
+    {
+        setName("TopicSample::Message");
+        m_typeSize = static_cast<uint32_t>(Message::getMaxCdrSerializedSize()) + 4 /*encapsulation*/;
+        m_isGetKeyDefined = Message::isKeyDefined();
+        size_t keyLength = Message::getKeyMaxCdrSerializedSize()>16 ? Message::getKeyMaxCdrSerializedSize() : 16;
+        m_keyBuffer = reinterpret_cast<unsigned char*>(malloc(keyLength));
+        memset(m_keyBuffer, 0, keyLength);
+    }
+
+    MessagePubSubType::~MessagePubSubType()
+    {
+        if(m_keyBuffer!=nullptr)
+            free(m_keyBuffer);
+    }
+
+    bool MessagePubSubType::serialize(void *data, SerializedPayload_t *payload)
+    {
+        Message *p_type = static_cast<Message*>(data);
+        eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast<char*>(payload->data), payload->max_size); // Object that manages the raw buffer.
+        eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN,
+                eprosima::fastcdr::Cdr::DDS_CDR); // Object that serializes the data.
+        payload->encapsulation = ser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE;
+        // Serialize encapsulation
+        ser.serialize_encapsulation();
+
+        try
+        {
+            p_type->serialize(ser); // Serialize the object:
+        }
+        catch(eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/)
+        {
+            return false;
+        }
+
+        payload->length = static_cast<uint32_t>(ser.getSerializedDataLength()); //Get the serialized length
+        return true;
+    }
+
+    bool MessagePubSubType::deserialize(SerializedPayload_t* payload, void* data)
+    {
+        Message* p_type = static_cast<Message*>(data); //Convert DATA to pointer of your type
+        eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast<char*>(payload->data), payload->length); // Object that manages the raw buffer.
+        eprosima::fastcdr::Cdr deser(fastbuffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN,
+                eprosima::fastcdr::Cdr::DDS_CDR); // Object that deserializes the data.
+        // Deserialize encapsulation.
+        deser.read_encapsulation();
+        payload->encapsulation = deser.endianness() == eprosima::fastcdr::Cdr::BIG_ENDIANNESS ? CDR_BE : CDR_LE;
+
+        try
+        {
+            p_type->deserialize(deser); //Deserialize the object:
+        }
+        catch(eprosima::fastcdr::exception::NotEnoughMemoryException& /*exception*/)
+        {
+            return false;
+        }
+
+        return true;
+    }
+
+    std::function<uint32_t()> MessagePubSubType::getSerializedSizeProvider(void* data)
+    {
+        return [data]() -> uint32_t
+        {
+            return static_cast<uint32_t>(type::getCdrSerializedSize(*static_cast<Message*>(data))) + 4 /*encapsulation*/;
+        };
+    }
+
+    void* MessagePubSubType::createData()
+    {
+        return reinterpret_cast<void*>(new Message());
+    }
+
+    void MessagePubSubType::deleteData(void* data)
+    {
+        delete(reinterpret_cast<Message*>(data));
+    }
+
+    bool MessagePubSubType::getKey(void *data, InstanceHandle_t* handle, bool force_md5)
+    {
+        if(!m_isGetKeyDefined)
+            return false;
+        Message* p_type = static_cast<Message*>(data);
+        eprosima::fastcdr::FastBuffer fastbuffer(reinterpret_cast<char*>(m_keyBuffer),Message::getKeyMaxCdrSerializedSize());     // Object that manages the raw buffer.
+        eprosima::fastcdr::Cdr ser(fastbuffer, eprosima::fastcdr::Cdr::BIG_ENDIANNESS);     // Object that serializes the data.
+        p_type->serializeKey(ser);
+        if(force_md5 || Message::getKeyMaxCdrSerializedSize()>16)    {
+            m_md5.init();
+            m_md5.update(m_keyBuffer, static_cast<unsigned int>(ser.getSerializedDataLength()));
+            m_md5.finalize();
+            for(uint8_t i = 0;i<16;++i)        {
+                handle->value[i] = m_md5.digest[i];
+            }
+        }
+        else    {
+            for(uint8_t i = 0;i<16;++i)        {
+                handle->value[i] = m_keyBuffer[i];
+            }
+        }
+        return true;
+    }
+
+
+} //End of namespace TopicSample

+ 61 - 0
src1/common/modulecomm_fastrtps/TopicsPubSubTypes.h

@@ -0,0 +1,61 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsPubSubTypes.h
+ * This header file contains the declaration of the serialization functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+
+#ifndef _TOPICSAMPLE_TOPICS_PUBSUBTYPES_H_
+#define _TOPICSAMPLE_TOPICS_PUBSUBTYPES_H_
+
+#include <fastrtps/config.h>
+#include <fastrtps/TopicDataType.h>
+
+#include "Topics.h"
+
+#if !defined(GEN_API_VER) || (GEN_API_VER != 1)
+#error Generated Topics is not compatible with current installed Fast-RTPS. Please, regenerate it with fastrtpsgen.
+#endif
+
+namespace TopicSample
+{
+    typedef std::vector<uint8_t> SomeBytes;
+    /*!
+     * @brief This class represents the TopicDataType of the type Message defined by the user in the IDL file.
+     * @ingroup TOPICS
+     */
+    class MessagePubSubType : public eprosima::fastrtps::TopicDataType {
+    public:
+        typedef Message type;
+
+        eProsima_user_DllExport MessagePubSubType();
+
+        eProsima_user_DllExport virtual ~MessagePubSubType();
+        eProsima_user_DllExport virtual bool serialize(void *data, eprosima::fastrtps::rtps::SerializedPayload_t *payload) override;
+        eProsima_user_DllExport virtual bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t *payload, void *data) override;
+        eProsima_user_DllExport virtual std::function<uint32_t()> getSerializedSizeProvider(void* data) override;
+        eProsima_user_DllExport virtual bool getKey(void *data, eprosima::fastrtps::rtps::InstanceHandle_t *ihandle,
+            bool force_md5 = false) override;
+        eProsima_user_DllExport virtual void* createData() override;
+        eProsima_user_DllExport virtual void deleteData(void * data) override;
+        MD5 m_md5;
+        unsigned char* m_keyBuffer;
+    };
+}
+
+#endif // _TOPICSAMPLE_TOPICS_PUBSUBTYPES_H_

+ 198 - 0
src1/common/modulecomm_fastrtps/TopicsPublisher.cxx

@@ -0,0 +1,198 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsPublisher.cpp
+ * This file contains the implementation of the publisher functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+
+#include <fastrtps/participant/Participant.h>
+#include <fastrtps/attributes/ParticipantAttributes.h>
+#include <fastrtps/publisher/Publisher.h>
+#include <fastrtps/attributes/PublisherAttributes.h>
+
+#include <fastrtps/Domain.h>
+
+#include <fastrtps/participant/Participant.h>
+#include <fastrtps/attributes/ParticipantAttributes.h>
+#include <fastrtps/attributes/PublisherAttributes.h>
+#include <fastrtps/publisher/Publisher.h>
+#include <fastrtps/Domain.h>
+#include <fastdds/rtps/transport/shared_mem/SharedMemTransportDescriptor.h>
+#include <fastdds/rtps/transport/UDPv4TransportDescriptor.h>
+
+#include <thread>
+#include <chrono>
+
+#include "TopicsPublisher.h"
+
+using namespace eprosima::fastrtps;
+using namespace eprosima::fastrtps::rtps;
+
+using namespace eprosima::fastdds::rtps;
+
+TopicsPublisher::TopicsPublisher() : mp_participant(nullptr), mp_publisher(nullptr) {}
+
+TopicsPublisher::~TopicsPublisher() {	Domain::removeParticipant(mp_participant);}
+
+bool TopicsPublisher::init(const char * strtopic)
+{
+    strncpy(mstrtopic,strtopic,255);
+    // Create RTPSParticipant
+
+    ParticipantAttributes PParam;
+    PParam.rtps.sendSocketBufferSize = 100000000;
+    PParam.rtps.setName("Participant_publisher");  //You can put here the name you want
+
+    PParam.rtps.builtin.discovery_config.discoveryProtocol = DiscoveryProtocol_t::SIMPLE;
+    PParam.rtps.builtin.discovery_config.use_SIMPLE_EndpointDiscoveryProtocol = true;
+    PParam.rtps.builtin.discovery_config.m_simpleEDP.use_PublicationReaderANDSubscriptionWriter = true;
+    PParam.rtps.builtin.discovery_config.m_simpleEDP.use_PublicationWriterANDSubscriptionReader = true;
+    PParam.rtps.builtin.discovery_config.leaseDuration = c_TimeInfinite;
+
+    // SharedMem transport configuration
+    PParam.rtps.useBuiltinTransports = false;
+
+    auto shm_transport = std::make_shared<SharedMemTransportDescriptor>();
+    shm_transport->segment_size(100*1024*1024);
+    PParam.rtps.userTransports.push_back(shm_transport);
+
+    // UDP
+    auto udp_transport = std::make_shared<UDPv4TransportDescriptor>();
+    //udp_transport->interfaceWhiteList.push_back("127.0.0.1");
+    PParam.rtps.userTransports.push_back(udp_transport);
+
+
+    mp_participant = Domain::createParticipant(PParam);
+    if(mp_participant == nullptr)
+    {
+        return false;
+    }
+
+    //Register the type
+
+    Domain::registerType(mp_participant, static_cast<TopicDataType*>(&myType));
+
+    // Create Publisher
+
+    PublisherAttributes Wparam;
+    Wparam.topic.topicKind = NO_KEY;
+    Wparam.topic.topicDataType = myType.getName();  //This type MUST be registered
+    Wparam.topic.topicName = strtopic;//"TopicsPubSubTopic";
+
+    Wparam.topic.historyQos.depth = 30;
+    Wparam.topic.resourceLimitsQos.max_samples = 50;
+    Wparam.topic.resourceLimitsQos.allocated_samples = 20;
+    Wparam.times.heartbeatPeriod.seconds = 2;
+    Wparam.times.heartbeatPeriod.nanosec = 200 * 1000 * 1000;
+    Wparam.qos.m_reliability.kind = RELIABLE_RELIABILITY_QOS;
+    Wparam.qos.m_publishMode.kind = ASYNCHRONOUS_PUBLISH_MODE;
+
+    mp_publisher = Domain::createPublisher(mp_participant,Wparam,static_cast<PublisherListener*>(&m_listener));
+
+    if(mp_publisher == nullptr)
+    {
+        return false;
+    }
+
+    std::cout << "Publisher created, waiting for Subscribers." << std::endl;
+    return true;
+}
+
+void TopicsPublisher::PubListener::onPublicationMatched(Publisher* pub,MatchingInfo& info)
+{
+    (void)pub;
+
+    if (info.status == MATCHED_MATCHING)
+    {
+        n_matched++;
+        std::cout << "Publisher matched" << std::endl;
+    }
+    else
+    {
+        n_matched--;
+        std::cout << "Publisher unmatched" << std::endl;
+    }
+}
+
+void TopicsPublisher::run()
+{
+    while(m_listener.n_matched == 0)
+    {
+        std::this_thread::sleep_for(std::chrono::milliseconds(250)); // Sleep 250 ms
+    }
+
+    // Publication code
+
+    TopicSample::Message st;
+
+    /* Initialize your structure here */
+
+    int msgsent = 0;
+    char ch = 'y';
+    do
+    {
+        if(ch == 'y')
+        {
+            mp_publisher->write(&st);  ++msgsent;
+            std::cout << "Sending sample, count=" << msgsent << ", send another sample?(y-yes,n-stop): ";
+        }
+        else if(ch == 'n')
+        {
+            std::cout << "Stopping execution " << std::endl;
+            break;
+        }
+        else
+        {
+            std::cout << "Command " << ch << " not recognized, please enter \"y/n\":";
+        }
+    } while(std::cin >> ch);
+}
+
+#include <QDateTime>
+
+void TopicsPublisher::senddata(const char *str, int nsize)
+{
+
+
+    static int ncount = 1;
+    std::cout<<"send data."<<std::endl;
+//    while(m_listener.n_matched == 0)
+    TopicSample::SomeBytes x;
+    x.resize(nsize);
+    memcpy(x.data(),str,nsize);
+
+    TopicSample::Message st;
+
+    st.msgname(mstrtopic);
+//    st.msgname("topictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopictopic");
+    st.counter(ncount);ncount++;
+    st.sendtime(QDateTime::currentMSecsSinceEpoch());
+    TopicSample::SomeBytes & px = x;
+    st.xdata(x);
+
+    int ndatasize = TopicSample::Message::getCdrSerializedSize(st);
+
+    std::cout<<"size is "<<ndatasize<<std::endl;
+
+
+    mp_publisher->write(&st);
+
+
+
+}
+

+ 56 - 0
src1/common/modulecomm_fastrtps/TopicsPublisher.h

@@ -0,0 +1,56 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsPublisher.h
+ * This header file contains the declaration of the publisher functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+
+#ifndef _TOPICSAMPLE_TOPICS_PUBLISHER_H_
+#define _TOPICSAMPLE_TOPICS_PUBLISHER_H_
+
+#include <fastrtps/fastrtps_fwd.h>
+#include <fastrtps/publisher/PublisherListener.h>
+
+#include "TopicsPubSubTypes.h"
+
+class TopicsPublisher
+{
+public:
+	TopicsPublisher();
+	virtual ~TopicsPublisher();
+    bool init(const char * strtopic);
+	void run();
+    void senddata(const char *str, int nsize);
+private:
+	eprosima::fastrtps::Participant *mp_participant;
+	eprosima::fastrtps::Publisher *mp_publisher;
+
+    char mstrtopic[256];
+
+	class PubListener : public eprosima::fastrtps::PublisherListener
+	{
+	public:
+		PubListener() : n_matched(0){};
+		~PubListener(){};
+		void onPublicationMatched(eprosima::fastrtps::Publisher* pub,eprosima::fastrtps::rtps::MatchingInfo& info);
+		int n_matched;
+	} m_listener;
+	TopicSample::MessagePubSubType myType;
+};
+
+#endif // _TOPICSAMPLE_TOPICS_PUBLISHER_H_

+ 206 - 0
src1/common/modulecomm_fastrtps/TopicsSubscriber.cxx

@@ -0,0 +1,206 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsSubscriber.cpp
+ * This file contains the implementation of the subscriber functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+#include <fastrtps/participant/Participant.h>
+#include <fastrtps/attributes/ParticipantAttributes.h>
+#include <fastrtps/subscriber/Subscriber.h>
+#include <fastrtps/attributes/SubscriberAttributes.h>
+
+#include <fastrtps/Domain.h>
+
+#include <fastcdr/FastBuffer.h>
+#include <fastcdr/FastCdr.h>
+#include <fastcdr/Cdr.h>
+
+#include <fastrtps/participant/Participant.h>
+#include <fastrtps/attributes/ParticipantAttributes.h>
+#include <fastrtps/attributes/PublisherAttributes.h>
+#include <fastrtps/publisher/Publisher.h>
+#include <fastrtps/Domain.h>
+#include <fastdds/rtps/transport/shared_mem/SharedMemTransportDescriptor.h>
+#include <fastdds/rtps/transport/UDPv4TransportDescriptor.h>
+
+#include "TopicsSubscriber.h"
+
+using namespace eprosima::fastrtps;
+using namespace eprosima::fastrtps::rtps;
+
+using namespace eprosima::fastdds::rtps;
+
+
+
+
+#include <QDateTime>
+
+TopicsSubscriber::TopicsSubscriber() : mp_participant(nullptr), mp_subscriber(nullptr) {}
+
+TopicsSubscriber::~TopicsSubscriber() {	Domain::removeParticipant(mp_participant);}
+
+bool TopicsSubscriber::init(const char * strtopic)
+{
+
+    strncpy(mstrtopic,strtopic,255);
+    // Create RTPSParticipant
+
+    ParticipantAttributes PParam;
+    PParam.rtps.setName("Participant_subscriber"); //You can put the name you want
+
+    PParam.rtps.builtin.discovery_config.discoveryProtocol = DiscoveryProtocol_t::SIMPLE;
+    PParam.rtps.builtin.discovery_config.use_SIMPLE_EndpointDiscoveryProtocol = true;
+    PParam.rtps.builtin.discovery_config.m_simpleEDP.use_PublicationReaderANDSubscriptionWriter = true;
+    PParam.rtps.builtin.discovery_config.m_simpleEDP.use_PublicationWriterANDSubscriptionReader = true;
+    PParam.rtps.builtin.discovery_config.leaseDuration = c_TimeInfinite;
+
+    // SharedMem transport configuration
+    PParam.rtps.useBuiltinTransports = false;
+
+    auto sm_transport = std::make_shared<SharedMemTransportDescriptor>();
+    sm_transport->segment_size(100*1024*1024);
+    PParam.rtps.userTransports.push_back(sm_transport);
+
+    // UDP
+    auto udp_transport = std::make_shared<UDPv4TransportDescriptor>();
+    //udp_transport->interfaceWhiteList.push_back("127.0.0.1");
+    PParam.rtps.userTransports.push_back(udp_transport);
+
+
+
+    mp_participant = Domain::createParticipant(PParam);
+    if(mp_participant == nullptr)
+    {
+        return false;
+    }
+
+    //Register the type
+
+    Domain::registerType(mp_participant, static_cast<TopicDataType*>(&myType));
+
+    // Create Subscriber
+
+    SubscriberAttributes Rparam;
+    Rparam.topic.topicKind = NO_KEY;
+    Rparam.topic.topicDataType = myType.getName(); //Must be registered before the creation of the subscriber
+    Rparam.topic.topicName = strtopic;//"TopicsPubSubTopic";
+
+    Rparam.topic.historyQos.depth = 30;
+    Rparam.topic.resourceLimitsQos.max_samples = 50;
+    Rparam.topic.resourceLimitsQos.allocated_samples = 20;
+
+    Rparam.qos.m_reliability.kind = RELIABLE_RELIABILITY_QOS;
+
+
+    mp_subscriber = Domain::createSubscriber(mp_participant,Rparam, static_cast<SubscriberListener*>(&m_listener));
+    if(mp_subscriber == nullptr)
+    {
+        return false;
+    }
+    return true;
+}
+
+void TopicsSubscriber::SubListener::onSubscriptionMatched(Subscriber* sub,MatchingInfo& info)
+{
+    (void)sub;
+
+    if (info.status == MATCHED_MATCHING)
+    {
+        n_matched++;
+        std::cout << "Subscriber matched" << std::endl;
+    }
+    else
+    {
+        n_matched--;
+        std::cout << "Subscriber unmatched" << std::endl;
+    }
+}
+
+
+void TopicsSubscriber::SubListener::setReceivedTopicFunction(ModuleFun xFun)
+{
+    mFun = xFun;
+    mbSetFun = true;
+}
+void TopicsSubscriber::SubListener::onNewDataMessage(Subscriber* sub)
+{
+    // Take data
+    TopicSample::Message st;
+    static int ncount = 0;
+
+    static int nmaxlatancy = 0;
+
+    std::cout<<"new msg"<<std::endl;
+
+
+//    char * strbuf = new char[1000000];
+//    eprosima::fastcdr::FastBuffer pbuf(strbuf,1000000);
+//    eprosima::fastcdr::Cdr * pxcdr;//
+//    pxcdr = new eprosima::fastcdr::Cdr(pbuf);
+
+//    if(sub->takeNextData(pxcdr, &m_info))
+//    {
+//        if(m_info.sampleKind == ALIVE)
+//        {
+//            // Print your structure data here.
+//            ++n_msg;
+//            std::cout << "Sample received, count=" << n_msg<<std::endl;
+//            st.deserialize(*pxcdr);
+
+//            std::cout<<" size is "<<TopicSample::Message::getCdrSerializedSize(st)<<std::endl;
+//        }
+//    }
+
+//    return;
+
+//    sub->get_first_untaken_info(&m_info);
+    std::cout<<"count is "<<sub->getUnreadCount()<<std::endl;
+
+    if(sub->takeNextData(&st, &m_info))
+    {
+        if(m_info.sampleKind == ALIVE)
+        {
+            // Print your structure data here.
+            ++n_msg;
+            ncount++;
+            std::cout << "Sample received, count=" << st.counter() <<" total: "<<ncount<<std::endl;
+            qint64 timex = QDateTime::currentMSecsSinceEpoch();
+            int nlatancy = (timex - st.sendtime());
+            if(nlatancy>nmaxlatancy)nmaxlatancy = nlatancy;
+            std::cout<<"  latency is "<<nlatancy<<" max: "<<nmaxlatancy<<std::endl;
+            std::cout<<" size is "<<st.xdata().size()<<std::endl;
+            QDateTime dt = QDateTime::fromMSecsSinceEpoch(st.sendtime());
+            if(mbSetFun) mFun((char *)(st.xdata().data()),st.xdata().size(),st.counter(),&dt,st.msgname().data());
+
+
+        }
+    }
+}
+
+void TopicsSubscriber::setReceivedTopicFunction(ModuleFun xFun)
+{
+    m_listener.setReceivedTopicFunction(xFun);
+}
+
+void TopicsSubscriber::run()
+{
+    std::cout << "Waiting for Data, press Enter to stop the Subscriber. "<<std::endl;
+    std::cin.ignore();
+    std::cout << "Shutting down the Subscriber." << std::endl;
+}
+

+ 72 - 0
src1/common/modulecomm_fastrtps/TopicsSubscriber.h

@@ -0,0 +1,72 @@
+// Copyright 2016 Proyectos y Sistemas de Mantenimiento SL (eProsima).
+//
+// 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.
+
+/*!
+ * @file TopicsSubscriber.h
+ * This header file contains the declaration of the subscriber functions.
+ *
+ * This file was generated by the tool fastcdrgen.
+ */
+
+
+#ifndef _TOPICSAMPLE_TOPICS_SUBSCRIBER_H_
+#define _TOPICSAMPLE_TOPICS_SUBSCRIBER_H_
+
+#include <fastrtps/fastrtps_fwd.h>
+#include <fastrtps/subscriber/SubscriberListener.h>
+#include <fastrtps/subscriber/SampleInfo.h>
+#include "TopicsPubSubTypes.h"
+
+
+#include <QDateTime>
+
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+
+class TopicsSubscriber
+{
+public:
+	TopicsSubscriber();
+	virtual ~TopicsSubscriber();
+    bool init(const char * strtopic);
+	void run();
+
+    void setReceivedTopicFunction(ModuleFun xFun);
+private:
+	eprosima::fastrtps::Participant *mp_participant;
+	eprosima::fastrtps::Subscriber *mp_subscriber;
+
+
+    char mstrtopic[256];
+
+	class SubListener : public eprosima::fastrtps::SubscriberListener
+	{
+	public:
+		SubListener() : n_matched(0),n_msg(0){};
+		~SubListener(){};
+		void onSubscriptionMatched(eprosima::fastrtps::Subscriber* sub,eprosima::fastrtps::rtps::MatchingInfo& info);
+		void onNewDataMessage(eprosima::fastrtps::Subscriber* sub);
+		eprosima::fastrtps::SampleInfo_t m_info;
+		int n_matched;
+		int n_msg;
+
+        void setReceivedTopicFunction(ModuleFun xFun);
+
+    private:
+        bool mbSetFun = false;
+        ModuleFun mFun;
+	} m_listener;
+	TopicSample::MessagePubSubType myType;
+};
+
+#endif // _TOPICSAMPLE_TOPICS_SUBSCRIBER_H_

+ 13 - 0
src1/common/modulecomm_fastrtps/ivmodulemsg_type.h

@@ -0,0 +1,13 @@
+#ifndef IVMODULEMSG_TYPE_H
+#define IVMODULEMSG_TYPE_H
+
+namespace iv {
+struct modulemsg_type
+{
+    char mstrmsgname[256];
+    int mnBufSize;
+    int mnMsgBufCount;
+};
+
+}
+#endif // IVMODULEMSG_TYPE_H

+ 63 - 0
src1/common/modulecomm_fastrtps/modulecomm_fastrtps.cpp

@@ -0,0 +1,63 @@
+#include "modulecomm_fastrtps.h".h"
+//#include "procsm_if.h"
+//#include "procsm.h"
+
+#include "modulecomm_impl.h"
+
+namespace iv {
+namespace modulecomm_fastrtps {
+
+
+void *  RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount)
+{
+
+
+    modulecomm_impl * pif = new modulecomm_impl(strcommname,modulecomm_impl::type_send);
+
+//    procsm_if * pif = new procsm_if(strcommname,nBufSize,nMsgBufCount,procsm::ModeWrite);
+    return (void *)pif;
+}
+
+void  *  RegisterRecv(const char * strcommname,SMCallBack pCall)
+{
+    modulecomm_impl * pif = new modulecomm_impl(strcommname,modulecomm_impl::type_recv);
+ //   procsm_if * pif = new procsm_if(strcommname,0,0,procsm::ModeRead);
+    pif->listenmsg(pCall);
+    return (void *)pif;
+}
+
+void * MODULECOMMFASTRTPSSHARED_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun)
+{
+    modulecomm_impl * pif = new modulecomm_impl(strcommname,modulecomm_impl::type_recv);
+ //   procsm_if * pif = new procsm_if(strcommname,0,0,procsm::ModeRead);
+    pif->listenmsg(xFun);
+    return (void *)pif;
+}
+void  ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen)
+{
+    modulecomm_impl * pif= (modulecomm_impl *)pHandle;
+ //   procsm_if * pif = (procsm_if *)pHandle;
+    pif->writemsg(strdata,nDataLen);
+}
+
+void  Unregister(void * pHandle)
+{
+    modulecomm_impl * pif= (modulecomm_impl *)pHandle;
+//    procsm_if * pif = (procsm_if *)pHandle;
+    delete pif;
+}
+
+void PauseComm(void *pHandle)
+{
+//    procsm_if * pif = (procsm_if *)pHandle;
+//    pif->pausecomm();
+}
+
+void ContintuComm(void *pHandle)
+{
+ //   procsm_if * pif = (procsm_if *)pHandle;
+ //   pif->continuecomm();
+}
+
+}
+}

+ 40 - 0
src1/common/modulecomm_fastrtps/modulecomm_fastrtps.h

@@ -0,0 +1,40 @@
+#ifndef MODULECOMM_FASTRTPS_H
+#define MODULECOMM_FASTRTPS_H
+
+#include <QtCore/qglobal.h>
+#include <QDateTime>
+
+#include <functional>
+
+#if defined(MODULECOMM_FASTRTPS_LIBRARY)
+#  define MODULECOMMFASTRTPSSHARED_EXPORT Q_DECL_EXPORT
+#else
+#  define MODULECOMMFASTRTPSSHARED_EXPORT Q_DECL_IMPORT
+#endif
+
+
+
+//#include <iostream>
+//#include <thread>
+
+//using namespace std::placeholders;
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+
+namespace iv {
+namespace modulecomm_fastrtps {
+void * MODULECOMMFASTRTPSSHARED_EXPORT RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount);
+void * MODULECOMMFASTRTPSSHARED_EXPORT RegisterRecv(const char * strcommname,SMCallBack pCall);
+void * MODULECOMMFASTRTPSSHARED_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun);
+void MODULECOMMFASTRTPSSHARED_EXPORT ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen);
+void MODULECOMMFASTRTPSSHARED_EXPORT Unregister(void * pHandle);
+void MODULECOMMFASTRTPSSHARED_EXPORT PauseComm(void * pHandle);
+void MODULECOMMFASTRTPSSHARED_EXPORT ContintuComm(void * pHandle);
+
+}
+
+}
+
+
+
+#endif 

+ 45 - 0
src1/common/modulecomm_fastrtps/modulecomm_fastrtps.pro

@@ -0,0 +1,45 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2018-07-10T05:46:48
+#
+#-------------------------------------------------
+
+QT       -= gui
+
+
+#DEFINES += dds_use_shm
+
+TARGET = modulecomm_fastrtps
+TEMPLATE = lib
+
+DEFINES += MODULECOMM_FASTRTPS_LIBRARY
+
+VERSION = 1.0.1
+CONFIG += plugin
+
+
+SOURCES += modulecomm_fastrtps.cpp \
+    Topics.cxx \
+    TopicsPubSubTypes.cxx \
+    TopicsPublisher.cxx \
+    TopicsSubscriber.cxx \
+    modulecomm_impl.cpp
+
+HEADERS += modulecomm_fastrtps.h \
+    Topics.h \
+    TopicsPubSubTypes.h \
+    TopicsPublisher.h \
+    TopicsSubscriber.h \
+    modulecomm_impl.h \
+    ivmodulemsg_type.h
+
+unix {
+    target.path = /usr/lib
+    INSTALLS += target
+}
+
+#INCLUDEPATH += $$PWD/../../../include/
+
+
+LIBS += -L$$PWD -lfastcdr -lfastrtps
+

+ 140 - 0
src1/common/modulecomm_fastrtps/modulecomm_impl.cpp

@@ -0,0 +1,140 @@
+#include "modulecomm_impl.h"
+
+#include <thread>
+#include <iostream>
+#include <QDateTime>
+
+#include <QMutex>
+#include <QFile>
+
+namespace iv {
+namespace modulecomm {
+QMutex gmodulecomm_dds_Mutex;
+int createcount = 0;
+}
+
+}
+
+
+void modulecomm_impl::callbackTopic(const char * strdata,const unsigned int nSize,const unsigned int index, QDateTime * dt,const char * strmemname) {
+
+  if(mbFunPlus)
+  {
+      mFun(strdata,nSize,index,dt,strmemname);
+  }
+  else
+  {
+     (*mpCall)(strdata,nSize,index,dt,strmemname);
+  }
+}
+
+
+int modulecomm_impl::GetTempConfPath(char *strpath)
+{
+    char strtmppath[256];
+    QDateTime dt = QDateTime::currentDateTime();
+    snprintf(strtmppath,256,"/tmp/adc_modulecomm_conf_%04d%02d%02d%02d%02d.ini",dt.date().year(),
+             dt.date().month(),dt.date().day(),dt.time().hour(),dt.time().minute());
+    QFile xFile;
+    xFile.setFileName(strtmppath);
+    char strtem[256];
+    char strdata[10000];
+    snprintf(strdata,10000,"");
+    if(!xFile.exists())
+    {
+        if(xFile.open(QIODevice::ReadWrite))
+        {
+            snprintf(strtem,256,"[common]\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"DCPSDefaultDiscovery=TheRTPSConfig\n");strncat(strdata,strtem,10000);
+#ifdef dds_use_shm
+            snprintf(strtem,256,"DCPSGlobalTransportConfig=myconfig\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"[config/myconfig]\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"transports=share\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"[transport/share]\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"transport_type=shmem\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"pool_size=100000000\n");strncat(strdata,strtem,10000);
+#endif
+            snprintf(strtem,256,"[rtps_discovery/TheRTPSConfig]\n");strncat(strdata,strtem,10000);
+            snprintf(strtem,256,"ResendPeriod=5\n");strncat(strdata,strtem,10000);
+            xFile.write(strdata,strnlen(strdata,10000));
+            xFile.close();
+        }
+    }
+    strncpy(strpath,strtmppath,255);
+    return 0;
+}
+
+modulecomm_impl::modulecomm_impl(const char * strcommname,int ntype )
+{
+
+    strncpy(mstrtopic,strcommname,255);
+
+    iv::modulecomm::gmodulecomm_dds_Mutex.lock();
+    if(ntype == type_recv)
+    {
+        mpSub = new TopicsSubscriber();
+        mpSub->init(strcommname);
+//        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+
+        mnType = type_recv;
+    }
+    else
+    {
+        mpPub = new TopicsPublisher();
+        mpPub->init(strcommname);
+ //       std::this_thread::sleep_for(std::chrono::milliseconds(10));
+        mnType = type_send;
+    }
+    iv::modulecomm::createcount++;
+    std::cout<<"count is "<<iv::modulecomm::createcount<<std::endl;
+    iv::modulecomm::gmodulecomm_dds_Mutex.unlock();
+
+}
+
+int modulecomm_impl::listenmsg(ModuleFun xFun)
+{
+    if(mnType == type_send)
+    {
+        std::cout<<"send not listen."<<std::endl;;
+        return -1;
+    }
+    mbFunPlus = true;
+    mFun = xFun;
+    ModuleFun topicFunction = std::bind(&modulecomm_impl::callbackTopic,this,std::placeholders::_1,
+                                                                                std::placeholders::_2,
+                                                                                std::placeholders::_3,
+                                                                                std::placeholders::_4,
+                                                                                std::placeholders::_5);
+    mpSub->setReceivedTopicFunction(topicFunction);
+    return 0;
+}
+
+int modulecomm_impl::listenmsg(SMCallBack pCall)
+{
+    if(mnType == type_send)
+    {
+        std::cout<<"send not listen."<<std::endl;
+        return -1;
+    }
+    mbFunPlus = false;
+    mpCall = pCall;
+    ModuleFun topicFunction = std::bind(&modulecomm_impl::callbackTopic,this,std::placeholders::_1,
+                                                                                std::placeholders::_2,
+                                                                                std::placeholders::_3,
+                                                                                std::placeholders::_4,
+                                                                                std::placeholders::_5);
+    mpSub->setReceivedTopicFunction(topicFunction);
+    return 0;
+}
+
+void modulecomm_impl::writemsg(const char *str, int nlen)
+{
+    if(mnType == type_recv)
+    {
+        std::cout<<"recv not send."<<std::endl;
+        return ;
+    }
+
+    mpPub->senddata(str,nlen);
+
+}

+ 41 - 0
src1/common/modulecomm_fastrtps/modulecomm_impl.h

@@ -0,0 +1,41 @@
+#ifndef MODULECOMM_IMPL_H
+#define MODULECOMM_IMPL_H
+
+#include <QDateTime>
+
+#include "TopicsPublisher.h"
+#include "TopicsSubscriber.h"
+
+
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+
+
+class modulecomm_impl
+{
+public:
+    const static int type_send = 1;
+    const static int type_recv = 2;
+public:
+    modulecomm_impl(const char * strcommname,int ntype = 2);
+    int listenmsg(SMCallBack pCall);
+    int listenmsg(ModuleFun xFun);
+    void writemsg(const char * str,int nlen);
+
+private:
+    char mstrtopic[256];
+    int mnType = type_recv;
+    TopicsPublisher * mpPub;
+    TopicsSubscriber * mpSub;
+    SMCallBack  mpCall;
+    ModuleFun mFun;
+    void callbackTopic(const char * strdata,const unsigned int nSize,const unsigned int index,QDateTime * dt,const char * strmemname);
+
+    int GetTempConfPath(char * strpath);
+
+
+
+    bool mbFunPlus = false;
+
+};
+
+#endif // MODULECOMM_IMPL_H

+ 73 - 0
src1/common/modulecomm_inter/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 480 - 0
src1/common/modulecomm_inter/intercomm.cpp

@@ -0,0 +1,480 @@
+#include "intercomm.h"
+
+#include <QMutex>
+#include <QWaitCondition>
+#include <iostream>
+
+namespace  iv {
+
+struct InterListenUnit
+{
+    QMutex mWaitMutex;
+    SMCallBack  mpCall;
+    ModuleFun mFun;
+    QWaitCondition * mpwc;
+    bool mbFunPlus = false;
+};
+
+struct interunit
+{
+    char strintername[256];
+    char * strdatabuf;
+    int nbufsize = 0;
+    int nPacCount;
+    QMutex mMutexUnit;
+    std::vector<InterListenUnit *> mvectorlisten;
+    QWaitCondition mwc;
+    bool mbHaveWriter = false;
+
+};
+
+std::vector<interunit *> gvectorinter;
+QMutex gMutexInter;
+
+
+static interunit * FindInterUnitByName(const char * strname)
+{
+    interunit * p = 0;
+    int i;
+    int nsize;
+    nsize = gvectorinter.size();
+    for(i=0;i<nsize;i++)
+    {
+        if(strncmp(strname,gvectorinter.at(i)->strintername,256) == 0)
+        {
+            return (gvectorinter.at(i));
+        }
+    }
+    return p;
+}
+
+
+intercomm::intercomm(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode)
+{
+    strncpy(mstrsmname,strsmname,256);
+
+    mnMode = nMode;
+    if(nMode == ModeWrite)
+    {
+        gMutexInter.lock();
+        interunit * p = FindInterUnitByName(strsmname);
+        if(p == 0)
+        {
+            interunit * pnewinter = new interunit;
+            strncpy(pnewinter->strintername,strsmname,256);
+            pnewinter->strdatabuf = new char[sizeof(procinter_info)+nMaxPacCount*sizeof(procinter_head) + nBufSize];
+            pnewinter->nPacCount = nMaxPacCount;
+            pnewinter->nbufsize = nBufSize;
+            gvectorinter.push_back(pnewinter);
+            mpa = pnewinter;
+
+
+        }
+        else
+        {
+            p->mMutexUnit.lock();
+            delete p->strdatabuf;
+            p->strdatabuf = new char[sizeof(procinter_info)+nMaxPacCount*sizeof(procinter_head) + nBufSize];
+            p->nPacCount = nMaxPacCount;
+            p->nbufsize = nBufSize;
+            p->mMutexUnit.unlock();
+            mpa = p;
+        }
+
+        interunit * pinter = (interunit * )mpa;
+        char * pdata = (char *)pinter->strdatabuf;
+        mpinfo = (procinter_info *)pdata;
+        mphead = (procinter_head *)(pdata+sizeof(procinter_info));
+        mpinfo->mCap = nMaxPacCount;
+        mpinfo->mnBufSize = nBufSize;
+        mpinfo->mFirst = 0;
+        mpinfo->mNext = 0;
+        mpinfo->mLock = 0;
+        pinter->mbHaveWriter = true;
+
+        gMutexInter.unlock();
+
+    }
+    else
+    {
+        gMutexInter.lock();
+        interunit * p = FindInterUnitByName(strsmname);
+        if(p == 0)
+        {
+            interunit * pnewinter = new interunit;
+            strncpy(pnewinter->strintername,strsmname,256);
+            gvectorinter.push_back(pnewinter);
+            mpa = pnewinter;
+        }
+        else
+        {
+            mpa = p;
+        }
+
+        interunit * pinter = (interunit * )mpa;
+        char * pdata = (char *)pinter->strdatabuf;
+        mpinfo = (procinter_info *)pdata;
+        mphead = (procinter_head *)(pdata+sizeof(procinter_info));
+
+        gMutexInter.unlock();
+    }
+}
+
+intercomm::~intercomm()
+{
+    if(mnMode == ModeRead)
+    {
+        stoplisten();
+        interunit * p = (interunit *)mpa;
+        p->mMutexUnit.lock();
+        InterListenUnit * plisten = (InterListenUnit *)mplistenunit;
+        int i;
+        for(i=0;i<p->mvectorlisten.size();i++)
+        {
+            if(plisten == p->mvectorlisten.at(i))
+            {
+                p->mvectorlisten.erase(p->mvectorlisten.begin() + i);
+                delete plisten;
+                break;
+            }
+        }
+        p->mMutexUnit.unlock();
+    }
+}
+
+int intercomm::listenmsg(ModuleFun xFun)
+{
+    if(mnMode == ModeWrite)
+    {
+        std::cout<<"intercomm::listenmsg this is Write. Can't Listen."<<std::endl;
+        return - 1;
+    }
+
+    interunit * p = (interunit *)mpa;
+    p->mMutexUnit.lock();
+    InterListenUnit * pnewlisten = new InterListenUnit;
+    pnewlisten->mbFunPlus = true;
+    pnewlisten->mFun = xFun;
+    pnewlisten->mpwc = &p->mwc;
+    p->mvectorlisten.push_back(pnewlisten);
+    p->mMutexUnit.unlock();
+
+    mplistenunit = (void *)pnewlisten;
+
+    mplistenthread = new std::thread(&intercomm::listernrun,this);
+    return 0;
+}
+
+int intercomm::listenmsg(SMCallBack pCall)
+{
+    if(mnMode == ModeWrite)
+    {
+        std::cout<<"intercomm::listenmsg this is Write. Can't Listen."<<std::endl;
+        return - 1;
+    }
+
+    interunit * p = (interunit *)mpa;
+    p->mMutexUnit.lock();
+    InterListenUnit * pnewlisten = new InterListenUnit;
+    pnewlisten->mbFunPlus = false;
+    pnewlisten->mpCall = pCall;
+    pnewlisten->mpwc = &p->mwc;
+    p->mvectorlisten.push_back(pnewlisten);
+    p->mMutexUnit.unlock();
+    mplistenunit = (void *)pnewlisten;
+    mplistenthread = new std::thread(&intercomm::listernrun,this);
+    return 0;
+}
+
+void intercomm::stoplisten()
+{
+    mblistenrun = false;
+    if(mplistenthread != 0)
+    {
+        mplistenthread->join();
+        mplistenthread = 0;
+    }
+}
+
+void intercomm::pausecomm()
+{
+    mbPause = true;
+}
+
+void intercomm::continuecomm()
+{
+    mbPause = false;
+}
+
+void intercomm::listernrun()
+{
+    InterListenUnit * pILU = (InterListenUnit * )mplistenunit;
+    QTime xTime;
+    xTime.start();
+    unsigned int nBufLen = 1;
+    unsigned int nRead;
+    char * str = new char[nBufLen];
+    unsigned int index =0;
+    QDateTime *pdt = new QDateTime();
+    interunit * pinter = (interunit *)mpa;
+    while(mblistenrun)
+    {
+        if(mbPause)
+        {
+            std::this_thread::sleep_for(std::chrono::milliseconds(100));
+            continue;
+        }
+        if(pinter->mbHaveWriter == false)
+        {
+            std::this_thread::sleep_for(std::chrono::milliseconds(100));
+            continue;
+        }
+        pILU->mWaitMutex.lock();
+        pILU->mpwc->wait(&pILU->mWaitMutex,100);
+        pILU->mWaitMutex.unlock();
+        int nRtn = readmsg(index,str,nBufLen,&nRead,pdt);
+        while ((nRtn != 0)&&(mblistenrun))
+        {
+            if(nRtn == -1)
+            {
+                nBufLen = nRead;
+                delete str;
+                if(nBufLen < 1)nBufLen = 1;
+                str = new char[nBufLen];
+            }
+            else
+            {
+                if(nRtn == -2)
+                {
+                   index = getcurrentnext();
+                }
+                else
+                {
+                   if(nRtn >0)
+                   {
+                       if(pILU->mbFunPlus)
+                       {
+                           pILU->mFun(str,nRtn,index,pdt,mstrsmname);
+                       }
+                       else
+                       {
+                          (*pILU->mpCall)(str,nRtn,index,pdt,mstrsmname);
+                       }
+                       index++;
+                   }
+                   else
+                   {
+                       std::this_thread::sleep_for(std::chrono::milliseconds(100));
+                   }
+                }
+            }
+            nRtn = readmsg(index,str,nBufLen,&nRead,pdt);
+        }
+
+    }
+
+    delete str;
+    delete pdt;
+}
+
+int intercomm::writemsg(const char *str, const unsigned int nSize)
+{
+    if(mbPause)return -2;
+    if(mnMode == ModeRead)
+    {
+        std::cout<<"Register read. can't write."<<std::endl;
+        return -1;
+    }
+    interunit * pinter = (interunit *)mpa;
+
+    pinter->mMutexUnit.lock();
+    char * pdata = (char *)pinter->strdatabuf;
+    mpinfo = (procinter_info *)pdata;
+    mphead = (procinter_head *)(pdata+sizeof(procinter_info));
+    if(nSize > pinter->nbufsize)
+    {
+        qDebug("procsm::writemsg message size is very big");
+        return -1;
+    }
+
+WRITEMSG:
+
+    char * pH,*pD;
+    QDateTime dt;
+    pH = (char *)pinter->strdatabuf;pH = pH + sizeof(procinter_info);
+    pD = (char *)pinter->strdatabuf;pD = pD + sizeof(procinter_info) + pinter->nPacCount * sizeof(procinter_head);
+    procinter_head * phh = (procinter_head *)pH;
+    unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+    if(nPac>=pinter->nPacCount)
+    {
+        unsigned int nRemove = pinter->nPacCount/3;
+        if(nRemove == 0)nRemove = 1;
+        MoveMem(nRemove);
+        goto WRITEMSG;
+    }
+    if(nPac == 0)
+    {
+        memcpy(pD,str,nSize);
+        dt = QDateTime::currentDateTime();
+        phh->SetDate(dt);
+        phh->mindex = mpinfo->mNext;
+        phh->mnPos = 0;
+        phh->mnLen = nSize;
+        mpinfo->mNext = mpinfo->mNext+1;
+    }
+    else
+    {
+        if(((phh+nPac-1)->mnPos+(phh+nPac-1)->mnLen + nSize)>=pinter->nbufsize)
+        {
+            unsigned int nRemove = pinter->nPacCount/2;
+            if(nRemove == 0)nRemove = 1;
+            MoveMem(nRemove);
+            goto WRITEMSG;
+        }
+        else
+        {
+            unsigned int nPos = (phh+nPac-1)->mnPos + (phh+nPac-1)->mnLen;
+            memcpy(pD+nPos,str,nSize);
+            dt = QDateTime::currentDateTime();
+            (phh+nPac)->SetDate(dt);
+            (phh+nPac)->mindex = mpinfo->mNext;
+            (phh+nPac)->mnPos = nPos;
+            (phh+nPac)->mnLen = nSize;
+            mpinfo->mNext = mpinfo->mNext+1;
+        }
+    }
+
+    const unsigned int nTM = 0x6fffffff;
+    if((mpinfo->mNext >nTM)&&(mpinfo->mFirst>nTM))
+    {
+       nPac = mpinfo->mNext - mpinfo->mFirst;
+       unsigned int i;
+       for(i=0;i<nPac;i++)
+       {
+           (phh+i)->mindex = (phh+i)->mindex-nTM;
+       }
+       mpinfo->mFirst = mpinfo->mFirst-nTM;
+       mpinfo->mNext = mpinfo->mNext - nTM;
+    }
+
+    pinter->mMutexUnit.unlock();
+    pinter->mwc.wakeAll();
+    return 0;
+}
+
+int intercomm::MoveMem(const unsigned int nSize)
+{
+    unsigned int nRemove = nSize;
+    if(nRemove == 0)return -1;
+    interunit * pinter = (interunit *)mpa;
+    char * pH,*pD;
+    pH = (char *)pinter->strdatabuf;pH = pH + sizeof(procinter_info);
+    pD = (char *)pinter->strdatabuf;pD = pD + sizeof(procinter_info) + pinter->nPacCount * sizeof(procinter_head);
+    procinter_head * phh = (procinter_head *)pH;
+    unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+
+    if(nRemove >nPac)
+    {
+        nRemove = nPac;
+    }
+
+    if(nRemove == nPac)
+    {
+        mpinfo->mFirst = mpinfo->mFirst + (unsigned int)nRemove;
+        return 0;
+    }
+
+    unsigned int i;
+    int nDataMove = 0;
+    for(i=0;i<nRemove;i++)
+    {
+        procinter_head * phd = phh+i;
+        nDataMove = nDataMove + phd->mnLen;
+    }
+    unsigned int nDataTotal;
+    for(i=0;i<(nPac - nRemove);i++)
+    {
+        memcpy(phh+i,phh+i+nRemove,sizeof(procinter_head));
+        (phh+i)->mnPos = (phh+i)->mnPos - nDataMove;
+    }
+    nDataTotal = (phh + nPac-nRemove-1)->mnPos + (phh+nPac-nRemove-1)->mnLen;
+    char * strtem = new char[pinter->nbufsize];
+    memcpy(strtem,pD+nDataMove,nDataTotal);
+    memcpy(pD,strtem,nDataTotal);
+    delete strtem;
+
+    mpinfo->mFirst = mpinfo->mFirst + (unsigned int)nRemove;
+    return 0;
+}
+
+int intercomm::readmsg(unsigned int index, char *str, unsigned int nMaxSize, unsigned int *nRead, QDateTime *pdt)
+{
+    int nRtn = 0;
+
+    interunit * pinter = (interunit *)mpa;
+
+    if(pinter->nbufsize == 0)return 0;
+    char * pdata = (char *)pinter->strdatabuf;
+    mpinfo = (procinter_info *)pdata;
+    mphead = (procinter_head *)(pdata+sizeof(procinter_info));
+
+    if((index< mpinfo->mFirst)||(index > mpinfo->mNext))
+    {
+        nRtn = -2;
+    }
+    if(nRtn != (-2))
+    {
+        if(index == mpinfo->mNext)
+        {
+            nRtn = 0;
+        }
+        else
+        {
+            char * pH,*pD;
+ //           pH = (char *)mpASM->data();pH = pH + 2*sizeof(unsigned int);
+
+ //           pD = (char *)mpASM->data();pD = pD + 2*sizeof(unsigned int) + mnMaxPacCount * sizeof(procsm_head);
+            pD = (char *)pinter->strdatabuf;pD = pD+ sizeof(procinter_info) + mpinfo->mCap*sizeof(procinter_head);
+            pH = (char *)pinter->strdatabuf;pH = pH+sizeof(procinter_info);
+            procinter_head * phh = (procinter_head *)pH;
+            unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+            if(nPac == 0)
+            {
+                nRtn = 0;
+            }
+            else
+            {
+                unsigned int nPos = index - mpinfo->mFirst;
+                *nRead = (phh+nPos)->mnLen;
+                if((phh+nPos)->mnLen > nMaxSize)
+                {
+                    nRtn = -1;
+
+                }
+                else
+                {
+        //            qDebug("read pos = %d",(phh+nPos)->mnPos);
+                   memcpy(str,pD + (phh+nPos)->mnPos,(phh+nPos)->mnLen);
+          //         qDebug("read pos = %d",(phh+nPos)->mnPos);
+                   nRtn = (phh+nPos)->mnLen;
+                   (phh+nPos)->GetDate(pdt);
+           //        memcpy(pdt,&((phh+nPos)->mdt),sizeof(QDateTime));
+                }
+            }
+        }
+    }
+    return nRtn;
+}
+
+unsigned int intercomm::getcurrentnext()
+{
+    unsigned int nNext;
+    interunit * pinter = (interunit *)mpa;
+    char * pdata = (char *)pinter->strdatabuf;
+    mpinfo = (procinter_info *)pdata;
+    mphead = (procinter_head *)(pdata+sizeof(procinter_info));
+    nNext = mpinfo->mNext;
+    return nNext;
+}
+
+}

+ 109 - 0
src1/common/modulecomm_inter/intercomm.h

@@ -0,0 +1,109 @@
+#ifndef INTERCOMM_H
+#define INTERCOMM_H
+
+#include <QDateTime>
+#include "vector"
+#include <functional>
+#include <thread>
+
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+using namespace std::placeholders;
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+
+
+class procinter_info
+{
+public:
+  unsigned int mFirst;
+  unsigned int mNext;
+  unsigned int mCap;
+  unsigned int mLock;
+  unsigned int mnBufSize;
+};
+
+class procinter_head
+{
+public:
+    unsigned short mYear;
+    unsigned char mMonth;
+    unsigned char mDay;
+    unsigned char mHour;
+    unsigned char mMinute;
+    unsigned char mSec;
+    unsigned short mMSec;
+    unsigned int mindex;
+    unsigned int mnPos;
+    unsigned int mnLen;
+public:
+    void SetDate(QDateTime dt)
+    {
+        mYear = dt.date().year();
+        mMonth = dt.date().month();
+        mDay = dt.date().day();
+        mHour = dt.time().hour();
+        mMinute = dt.time().minute();
+        mSec = dt.time().second();
+        mMSec = dt.time().msec();
+    }
+    void GetDate(QDateTime * pdt)
+    {
+        QDate dt;
+        dt.setDate(mYear,mMonth,mDay);
+        QTime time;
+        time.setHMS(mHour,mMinute,mSec,mMSec);
+        pdt->setDate(dt);
+        pdt->setTime(time);
+
+    }
+};
+
+
+namespace  iv {
+
+class intercomm
+{
+public:
+    intercomm(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode);
+    ~intercomm();
+
+    int listenmsg(SMCallBack pCall);
+    int listenmsg(ModuleFun xFun);
+    void stoplisten();
+
+    void pausecomm();
+    void continuecomm();
+
+    const static int ModeRead = 1;
+    const static int ModeWrite = 0;
+
+    int writemsg(const char * str,const unsigned int nSize);
+
+private:
+
+
+    char mstrsmname[256];
+    int mnMode;
+    void * mpa;
+    void * mplistenunit;
+
+private:
+    void listernrun();
+    bool mblistenrun = true;
+    bool mbPause = false;
+    std::thread * mplistenthread = 0;
+
+    procinter_info * mpinfo;
+    procinter_head * mphead;
+
+
+private:
+
+    int readmsg(unsigned int index,char * str,unsigned int nMaxSize,unsigned int * nRead,QDateTime * pdt);
+    int MoveMem(const unsigned int nSize);
+    unsigned int getcurrentnext();
+};
+}
+
+
+
+#endif // INTERCOMM_H

+ 56 - 0
src1/common/modulecomm_inter/modulecomm_inter.cpp

@@ -0,0 +1,56 @@
+#include "modulecomm_inter.h"
+#include <iostream>
+
+#include "intercomm.h"
+
+namespace iv {
+namespace modulecomm_inter {
+
+void *  RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount)
+{
+    iv::intercomm * pinter = new iv::intercomm(strcommname,nBufSize,nMsgBufCount,iv::intercomm::ModeWrite);
+    return (void *)pinter;
+}
+
+void  *  RegisterRecv(const char * strcommname,SMCallBack pCall)
+{
+    iv::intercomm * pif = new iv::intercomm(strcommname,0,0,iv::intercomm::ModeRead);
+    pif->listenmsg(pCall);
+    return (void *)pif;
+}
+
+void * MODULECOMM_INTER_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun)
+{
+    iv::intercomm * pif = new iv::intercomm(strcommname,0,0,iv::intercomm::ModeRead);
+    pif->listenmsg(xFun);
+    return (void *)pif;
+}
+void  ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen)
+{
+    iv::intercomm * pif = (iv::intercomm *)pHandle;
+    pif->writemsg(strdata,nDataLen);
+}
+
+void  Unregister(void * pHandle)
+{
+    iv::intercomm * pif = (iv::intercomm *)pHandle;
+    delete pif;
+}
+
+void PauseComm(void *pHandle)
+{
+    iv::intercomm * pif = (iv::intercomm *)pHandle;
+    pif->pausecomm();
+}
+
+void ContintuComm(void *pHandle)
+{
+    iv::intercomm * pif = (iv::intercomm *)pHandle;
+    pif->continuecomm();
+}
+
+}
+}
+
+
+

+ 37 - 0
src1/common/modulecomm_inter/modulecomm_inter.h

@@ -0,0 +1,37 @@
+#ifndef MODULECOMM_INTER_H
+#define MODULECOMM_INTER_H
+
+#include <QtCore/qglobal.h>
+
+#include <functional>
+#include <QDateTime>
+
+#if defined(MODULECOMM_INTER_LIBRARY)
+#  define MODULECOMM_INTER_EXPORT Q_DECL_EXPORT
+#else
+#  define MODULECOMM_INTER_EXPORT Q_DECL_IMPORT
+#endif
+
+#ifndef IV_MODULE_FUN
+
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+#define IV_MODULE_FUN
+#endif
+
+
+namespace iv {
+namespace modulecomm_inter {
+void * MODULECOMM_INTER_EXPORT RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount);
+void * MODULECOMM_INTER_EXPORT RegisterRecv(const char * strcommname,SMCallBack pCall);
+void * MODULECOMM_INTER_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun);
+void MODULECOMM_INTER_EXPORT ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen);
+void MODULECOMM_INTER_EXPORT Unregister(void * pHandle);
+void MODULECOMM_INTER_EXPORT PauseComm(void * pHandle);
+void MODULECOMM_INTER_EXPORT ContintuComm(void * pHandle);
+
+}
+
+}
+
+#endif // MODULECOMM_INTER_H

+ 33 - 0
src1/common/modulecomm_inter/modulecomm_inter.pro

@@ -0,0 +1,33 @@
+QT -= gui
+
+TEMPLATE = lib
+DEFINES += MODULECOMM_INTER_LIBRARY
+
+CONFIG += c++11
+
+CONFIG += plugin
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+    intercomm.cpp \
+    modulecomm_inter.cpp
+
+HEADERS += \
+    intercomm.h \
+    modulecomm_inter.h
+
+# Default rules for deployment.
+unix {
+    target.path = /usr/lib
+}
+!isEmpty(target.path): INSTALLS += target

+ 90 - 0
src1/common/modulecomm_shm/ReadMe.md

@@ -0,0 +1,90 @@
+# How to use share memory
+
+共享内存使用分为发送端和接收端,以下分别介绍
+
+## 发送端
+
+**1. 添加共享内存消息格式文件**
+
+共享内存中数据采用protobuf格式存储,Protobuf是一种平台无关、语言无关、可扩展且轻便高效的序列化数据结构的协议,可以用于**网络通信**和**数据存储**。
+
+为使用共享内存,需添加一个相应的proto文件,文件位于`modularization/src/include/proto/hmi.proto`,可参考已有的文件编写
+
+```protobuf
+syntax = "proto2";
+package iv.hmi;
+message hmimsg
+{
+ required bool mbPause = 1;
+ required bool mbBocheMode = 2;
+ required bool mbbusmode = 3;
+};
+```
+
+**2. 注册共享内存**
+
+在工程配置文件***.pro中添加引用信息:
+
+```
+SOURCES += \
+    ../../include/msgtype/ui.pb.cc
+HEADERS += \   
+    ../../include/msgtype/ui.pb.h
+LIBS += -lprotobuf
+INCLUDEPATH += $$PWD/../../include/msgtype
+LIBS += -L$$PWD/../../../bin/ -lmodulecomm 
+```
+
+设置共享内存名并注册:
+
+```c++
+std::string strmemvbox = "test"
+gpa = iv::modulecomm::RegisterSend(strmemvbox.data(),100000,3);iv::modulecomm::RegisterSend(strmemvbox.data(),100000,3);
+```
+
+写入数据:
+
+```c++
+char * str = new char[gobj.ByteSize()]; //gobj是一个probuf数据,使用方法参考protobuf的使用
+int nsize = gobj.ByteSize();
+if(gobj.SerializeToArray(str,nsize))
+{
+    iv::modulecomm::ModuleSendMsg(gpa,str,nsize);
+}
+```
+
+## 接收端
+
+**从共享内中读取数据**
+
+工程配置文件中添加配置信息:
+
+```pro
+SOURCES += \
+    ../../include/msgtype/ui.pb.cc
+HEADERS += \   
+    ../../include/msgtype/ui.pb.h
+LIBS += -lprotobuf
+INCLUDEPATH += $$PWD/../../include/msgtype
+LIBS += -L$$PWD/../../../bin/ -lmodulecomm 
+```
+
+源码中实现:
+
+```c++
+std::string strmemcan = “test”;//设置共享内存名字
+iv::modulecomm::RegisterRecv(strmemcan.data(),listen); 
+//数据接收函数,共享内存收到数据时,会调用:
+void listen(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    if(nSize<1)return;
+    iv::can::canmsg xmsg;
+    if(false == xmsg.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<"esr Listencan0 fail."<<std::endl;
+        return;
+    }
+    DecodeVboxData(xmsg);
+}
+```
+

+ 13 - 0
src1/common/modulecomm_shm/ivmodulemsg_type.h

@@ -0,0 +1,13 @@
+#ifndef IVMODULEMSG_TYPE_H
+#define IVMODULEMSG_TYPE_H
+
+namespace iv {
+struct modulemsg_type
+{
+    char mstrmsgname[256];
+    int mnBufSize;
+    int mnMsgBufCount;
+};
+
+}
+#endif // IVMODULEMSG_TYPE_H

+ 54 - 0
src1/common/modulecomm_shm/modulecomm_shm.cpp

@@ -0,0 +1,54 @@
+#include "modulecomm_shm.h"
+#include "procsm_if.h"
+#include "procsm.h"
+#include <iostream>
+
+namespace iv {
+namespace modulecomm_shm {
+
+void *  RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount)
+{
+
+    procsm_if * pif = new procsm_if(strcommname,nBufSize,nMsgBufCount,procsm::ModeWrite);
+    return (void *)pif;
+}
+
+void  *  RegisterRecv(const char * strcommname,SMCallBack pCall)
+{
+    procsm_if * pif = new procsm_if(strcommname,0,0,procsm::ModeRead);
+    pif->listenmsg(pCall);
+    return (void *)pif;
+}
+
+void * MODULECOMMSHARED_SHM_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun)
+{
+    procsm_if * pif = new procsm_if(strcommname,0,0,procsm::ModeRead);
+    pif->listenmsg(xFun);
+    return (void *)pif;
+}
+void  ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen)
+{
+    procsm_if * pif = (procsm_if *)pHandle;
+    pif->writemsg(strdata,nDataLen);
+}
+
+void  Unregister(void * pHandle)
+{
+    procsm_if * pif = (procsm_if *)pHandle;
+    delete pif;
+}
+
+void PauseComm(void *pHandle)
+{
+    procsm_if * pif = (procsm_if *)pHandle;
+    pif->pausecomm();
+}
+
+void ContintuComm(void *pHandle)
+{
+    procsm_if * pif = (procsm_if *)pHandle;
+    pif->continuecomm();
+}
+
+}
+}

+ 42 - 0
src1/common/modulecomm_shm/modulecomm_shm.h

@@ -0,0 +1,42 @@
+#ifndef MODULECOMM_SHM_H
+#define MODULECOMM_SHM_H
+
+#include <QtCore/qglobal.h>
+#include <QDateTime>
+
+#include <functional>
+
+#if defined(MODULECOMM_SHM_LIBRARY)
+#  define MODULECOMMSHARED_SHM_EXPORT Q_DECL_EXPORT
+#else
+#  define MODULECOMMSHARED_SHM_EXPORT Q_DECL_IMPORT
+#endif
+
+
+
+//#include <iostream>
+//#include <thread>
+
+#ifndef IV_MODULE_FUN
+
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+#define IV_MODULE_FUN
+#endif
+namespace iv {
+namespace modulecomm_shm {
+void * MODULECOMMSHARED_SHM_EXPORT RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount);
+void * MODULECOMMSHARED_SHM_EXPORT RegisterRecv(const char * strcommname,SMCallBack pCall);
+void * MODULECOMMSHARED_SHM_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun);
+void MODULECOMMSHARED_SHM_EXPORT ModuleSendMsg(void * pHandle,const char * strdata,const unsigned int nDataLen);
+void MODULECOMMSHARED_SHM_EXPORT Unregister(void * pHandle);
+void MODULECOMMSHARED_SHM_EXPORT PauseComm(void * pHandle);
+void MODULECOMMSHARED_SHM_EXPORT ContintuComm(void * pHandle);
+
+}
+
+}
+
+
+
+#endif 

+ 41 - 0
src1/common/modulecomm_shm/modulecomm_shm.pro

@@ -0,0 +1,41 @@
+#-------------------------------------------------
+#
+# Project created by QtCreator 2018-07-10T05:46:48
+#
+#-------------------------------------------------
+
+QT       -= gui
+
+QT       += dbus
+
+
+#DEFINES += USELCM
+
+DEFINES += USEDBUS
+
+TARGET = modulecomm_shm
+TEMPLATE = lib
+
+DEFINES += MODULECOMM_SHM_LIBRARY
+
+#VERSION = 1.0.1
+CONFIG += plugin
+
+
+SOURCES += modulecomm_shm.cpp \
+    procsm.cpp \
+    procsm_if.cpp
+
+HEADERS += modulecomm_shm.h \
+    procsm.h \
+    procsm_if.h \
+    ivmodulemsg_type.h
+
+unix {
+    target.path = /usr/lib
+    INSTALLS += target
+}
+
+#INCLUDEPATH += $$PWD/../../../include/
+LIBS += -L$$PWD
+

+ 378 - 0
src1/common/modulecomm_shm/procsm.cpp

@@ -0,0 +1,378 @@
+#include <iostream>
+#include <thread>
+#include <QTime>
+#include <QThread>
+
+#include "procsm.h"
+
+
+class AttachThread : public QThread
+{
+  public:
+    AttachThread(QSharedMemory * pa,bool & bAttach)
+    {
+       mbAttach = bAttach;
+       mpa = pa;
+       mbrun = true;
+    }
+    QSharedMemory * mpa;
+    bool mbAttach = false;
+    bool mbrun = true;
+    void run()
+    {
+        mbAttach = mpa->attach();
+        mbrun = false;
+    }
+};
+
+procsm::procsm(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode)
+{
+//    mnBufSize = nBufSize;
+
+//    qDebug("create dbus");
+
+    mpASM = new QSharedMemory(strsmname);
+
+    if(nMode == ModeWrite)
+    {
+
+        mmodulemsg_type.mnBufSize = nBufSize;
+        mmodulemsg_type.mnMsgBufCount = nMaxPacCount;
+        strncpy(mmodulemsg_type.mstrmsgname,strsmname,255);
+#ifdef USEDBUS
+        mmsg = QDBusMessage::createSignal("/catarc/adc",  "adc.adciv.modulecomm", strsmname);
+        mmsg<<1;
+#endif
+
+        bool bAttach = false;
+        AttachThread AT(mpASM,bAttach);
+        AT.start();
+        QTime xTime;
+        xTime.start();
+        while(xTime.elapsed()<100)
+        {
+            if(AT.mbrun == false)
+            {
+                bAttach = AT.mbAttach;
+                break;
+            }
+        }
+ //       qDebug("time is %d",xTime.elapsed());
+        if(xTime.elapsed()>= 1000)
+        {
+            qDebug("in 1000ms Attach fail.terminate it .");
+            AT.terminate();
+            bAttach = false;
+        }
+
+ //       if(!mpASM->attach())
+        if(!bAttach)
+        {
+
+            mpASM->create(sizeof(procsm_info)+nMaxPacCount*sizeof(procsm_head) + nBufSize);
+            char * p = (char *)mpASM->data();
+            mpinfo = (procsm_info *)p;
+            mphead = (procsm_head *)(p+sizeof(procsm_info));
+            mpinfo->mCap = nMaxPacCount;
+            mpinfo->mnBufSize = nBufSize;
+            mpinfo->mFirst = 0;
+            mpinfo->mNext = 0;
+            mpinfo->mLock = 0;
+        }
+
+
+
+
+        if(mpASM->isAttached())
+        {
+
+            mbAttach = true;
+            char * p = (char *)mpASM->data();
+            mpinfo = (procsm_info *)p;
+            mphead = (procsm_head *)(p+sizeof(procsm_info));
+            mnMaxPacCount = mpinfo->mCap;
+            mnBufSize = mpinfo->mnBufSize;
+    //        qDebug("attach successful");
+            mstrtem = new char[mnBufSize];
+
+#ifdef USEDBUS
+            mmsgres = QDBusMessage::createSignal("/catarc/adc",  "adciv.interface", "modulemsgres");
+            mmsgres<<1;
+
+            bool bconnect = QDBusConnection::sessionBus().connect(QString(),"/catarc/adc",  "adciv.interface", "modulemsgquery",this,SLOT(onQuery()));
+            if(bconnect == false)
+            {
+                std::cout<<"procsm_if_readthread::procsm_if_readthread bconect is false"<<std::endl;
+            }
+#endif
+        }
+        else
+        {
+          mbAttach = false;
+            qDebug("Share Memory Error.");
+        }
+
+
+    }
+}
+
+#ifdef USEDBUS
+    void procsm::onQuery()
+    {
+        QByteArray ba;
+        ba.append((char *)&mmodulemsg_type,sizeof(iv::modulemsg_type));
+
+        QList<QVariant> x;
+        x<<ba;
+        mmsgres.setArguments(x);
+        QDBusConnection::sessionBus().send(mmsgres);
+    }
+
+#endif
+
+bool procsm::AttachMem()
+{
+    mpASM->attach();
+    if(mpASM->isAttached())
+    {
+        mbAttach = true;
+        char * p = (char *)mpASM->data();
+        mpinfo = (procsm_info *)p;
+        mphead = (procsm_head *)(p+sizeof(procsm_info));
+        mnMaxPacCount = mpinfo->mCap;
+        mnBufSize = mpinfo->mnBufSize;
+        return true;
+    }
+    else
+    {
+        return false;
+    }
+}
+
+int procsm::MoveMem(const unsigned int nSize)
+{
+//    qDebug("move mem");
+     unsigned int nRemove = nSize;
+     if(nRemove == 0)return -1;
+
+//     unsigned int * pIndexFirst = (unsigned int *)mpASM->data();
+//     unsigned int * pIndexNext = pIndexFirst+1;
+//     qDebug("first = %d next = %d",*pIndexFirst,*pIndexNext);
+//    unsigned int * pIndexNext = pIndexFirst;
+    char * pH,*pD;
+    pH = (char *)mpASM->data();pH = pH + sizeof(procsm_info);
+    pD = (char *)mpASM->data();pD = pD + sizeof(procsm_info) + mnMaxPacCount * sizeof(procsm_head);
+    procsm_head * phh = (procsm_head *)pH;
+    unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+
+    if(nRemove >nPac)
+    {
+  //      qDebug("procsm::MoveMem nRemove > nPac nRemove = %d",nRemove);
+        nRemove = nPac;
+    }
+
+    if(nRemove == nPac)
+    {
+        mpinfo->mFirst = mpinfo->mFirst + (unsigned int)nRemove;
+        return 0;
+    }
+
+    unsigned int i;
+    int nDataMove = 0;
+    for(i=0;i<nRemove;i++)
+    {
+        procsm_head * phd = phh+i;
+        nDataMove = nDataMove + phd->mnLen;
+    }
+    unsigned int nDataTotal;
+    for(i=0;i<(nPac - nRemove);i++)
+    {
+        memcpy(phh+i,phh+i+nRemove,sizeof(procsm_head));
+        (phh+i)->mnPos = (phh+i)->mnPos - nDataMove;
+    }
+    nDataTotal = (phh + nPac-nRemove-1)->mnPos + (phh+nPac-nRemove-1)->mnLen;
+    memcpy(mstrtem,pD+nDataMove,nDataTotal);
+    memcpy(pD,mstrtem,nDataTotal);
+
+//    for(i=0;i<nDataTotal;i++)
+//    {
+//        *(pD+i) = *(pD+i+nDataMove);
+//    }
+    mpinfo->mFirst = mpinfo->mFirst + (unsigned int)nRemove;
+    return 0;
+}
+
+int procsm::writemsg(const char *str, const unsigned int nSize)
+{
+    if(nSize > mnBufSize)
+    {
+        qDebug("procsm::writemsg message size is very big");
+        return -1;
+    }
+    if(mbAttach == false)
+    {
+        std::cout<<"ShareMemory Attach fail."<<std::endl;
+        return -1;
+    }
+    mpASM->lock();
+
+
+
+//    unsigned int * pIndexFirst = (unsigned int *)mpASM->data();
+//    unsigned int * pIndexNext = pIndexFirst+1;
+    if(mpinfo->mLock == 1)
+    {
+        std::cout<<"ShareMemory have lock.Init."<<std::endl;
+        mpinfo->mLock = 0;
+        mpinfo->mFirst = 0;
+        mpinfo->mNext = 0;
+    }
+    mpinfo->mLock =1;
+WRITEMSG:
+    char * pH,*pD;
+    QDateTime dt;
+    pH = (char *)mpASM->data();pH = pH + sizeof(procsm_info);
+    pD = (char *)mpASM->data();pD = pD + sizeof(procsm_info) + mnMaxPacCount * sizeof(procsm_head);
+    procsm_head * phh = (procsm_head *)pH;
+    unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+    if(nPac>=mnMaxPacCount)
+    {
+        unsigned int nRemove = mnMaxPacCount/3;
+        if(nRemove == 0)nRemove = 1;
+        MoveMem(nRemove);
+        goto WRITEMSG;
+    }
+    if(nPac == 0)
+    {
+        memcpy(pD,str,nSize);
+        dt = QDateTime::currentDateTime();
+    //    phh->mdt = dt;
+        phh->SetDate(dt);
+   //     memcpy(&phh->mdt,&dt,sizeof(QDateTime));
+   //     phh->mdt = QDateTime::currentDateTime();
+        phh->mindex = mpinfo->mNext;
+        phh->mnPos = 0;
+        phh->mnLen = nSize;
+        mpinfo->mNext = mpinfo->mNext+1;
+    }
+    else
+    {
+        if(((phh+nPac-1)->mnPos+(phh+nPac-1)->mnLen + nSize)>=mnBufSize)
+        {
+            unsigned int nRemove = mnMaxPacCount/2;
+            if(nRemove == 0)nRemove = 1;
+            MoveMem(nRemove);
+            goto WRITEMSG;
+        }
+        else
+        {
+            unsigned int nPos = (phh+nPac-1)->mnPos + (phh+nPac-1)->mnLen;
+     //       qDebug("write pos = %d",nPos);
+            memcpy(pD+nPos,str,nSize);
+            dt = QDateTime::currentDateTime();
+            (phh+nPac)->SetDate(dt);
+ //           memcpy(&(phh+nPac)->mdt,&dt,sizeof(QDateTime));
+ //           (phh+nPac)->mdt = QDateTime::currentDateTime();
+            (phh+nPac)->mindex = mpinfo->mNext;
+            (phh+nPac)->mnPos = nPos;
+            (phh+nPac)->mnLen = nSize;
+            mpinfo->mNext = mpinfo->mNext+1;
+        }
+    }
+
+    const unsigned int nTM = 0x6fffffff;
+    if((mpinfo->mNext >nTM)&&(mpinfo->mFirst>nTM))
+    {
+       nPac = mpinfo->mNext - mpinfo->mFirst;
+       unsigned int i;
+       for(i=0;i<nPac;i++)
+       {
+           (phh+i)->mindex = (phh+i)->mindex-nTM;
+       }
+       mpinfo->mFirst = mpinfo->mFirst-nTM;
+       mpinfo->mNext = mpinfo->mNext - nTM;
+    }
+
+    mpinfo->mLock = 0;
+    mpASM->unlock();
+#ifdef USEDBUS
+    QDBusConnection::sessionBus().send(mmsg);
+#endif
+    return 0;
+}
+
+unsigned int procsm::getcurrentnext()
+{
+
+
+    unsigned int nNext;
+    mpASM->lock();
+    nNext = mpinfo->mNext;
+    mpASM->unlock();
+    return nNext;
+}
+
+
+//if return 0 No Data.
+//if return -1 nMaxSize is small
+//if retrun -2 index is not in range,call getcurrentnext get position
+//if return > 0 readdata
+int procsm::readmsg(unsigned int index, char *str, unsigned int nMaxSize,unsigned int * nRead,QDateTime * pdt)
+{
+    if(mbAttach == false)
+    {
+        std::cout<<"ShareMemory Attach fail."<<std::endl;
+        return -1;
+    }
+    int nRtn = 0;
+    mpASM->lock();
+
+    if((index< mpinfo->mFirst)||(index > mpinfo->mNext))
+    {
+        nRtn = -2;
+    }
+    if(nRtn != (-2))
+    {
+        if(index == mpinfo->mNext)
+        {
+            nRtn = 0;
+        }
+        else
+        {
+            char * pH,*pD;
+ //           pH = (char *)mpASM->data();pH = pH + 2*sizeof(unsigned int);
+
+ //           pD = (char *)mpASM->data();pD = pD + 2*sizeof(unsigned int) + mnMaxPacCount * sizeof(procsm_head);
+            pD = (char *)mpASM->data();pD = pD+ sizeof(procsm_info) + mpinfo->mCap*sizeof(procsm_head);
+            pH = (char *)mpASM->data();pH = pH+sizeof(procsm_info);
+            procsm_head * phh = (procsm_head *)pH;
+            unsigned int nPac = mpinfo->mNext - mpinfo->mFirst;
+            if(nPac == 0)
+            {
+                nRtn = 0;
+            }
+            else
+            {
+                unsigned int nPos = index - mpinfo->mFirst;
+                *nRead = (phh+nPos)->mnLen;
+                if((phh+nPos)->mnLen > nMaxSize)
+                {
+                    nRtn = -1;
+
+                }
+                else
+                {
+        //            qDebug("read pos = %d",(phh+nPos)->mnPos);
+                   memcpy(str,pD + (phh+nPos)->mnPos,(phh+nPos)->mnLen);
+          //         qDebug("read pos = %d",(phh+nPos)->mnPos);
+                   nRtn = (phh+nPos)->mnLen;
+                   (phh+nPos)->GetDate(pdt);
+           //        memcpy(pdt,&((phh+nPos)->mdt),sizeof(QDateTime));
+                }
+            }
+        }
+    }
+    mpASM->unlock();
+    return nRtn;
+}
+

+ 112 - 0
src1/common/modulecomm_shm/procsm.h

@@ -0,0 +1,112 @@
+#ifndef PROCSM_H
+#define PROCSM_H
+
+#include <QThread>
+#include <QSharedMemory>
+#include <QDateTime>
+#include <QList>
+#include <QVariant>
+
+#ifdef USEDBUS
+#include <QtDBus/QDBusMessage>
+#include <QtDBus/QDBusConnection>
+
+#endif
+
+#include "ivmodulemsg_type.h"
+
+class procsm_info
+{
+public:
+  unsigned int mFirst;
+  unsigned int mNext;
+  unsigned int mCap;
+  unsigned int mLock;
+  unsigned int mnBufSize;
+};
+
+class procsm_head
+{
+public:
+    unsigned short mYear;
+    unsigned char mMonth;
+    unsigned char mDay;
+    unsigned char mHour;
+    unsigned char mMinute;
+    unsigned char mSec;
+    unsigned short mMSec;
+    unsigned int mindex;
+    unsigned int mnPos;
+    unsigned int mnLen;
+public:
+    void SetDate(QDateTime dt)
+    {
+        mYear = dt.date().year();
+        mMonth = dt.date().month();
+        mDay = dt.date().day();
+        mHour = dt.time().hour();
+        mMinute = dt.time().minute();
+        mSec = dt.time().second();
+        mMSec = dt.time().msec();
+    }
+    void GetDate(QDateTime * pdt)
+    {
+        QDate dt;
+        dt.setDate(mYear,mMonth,mDay);
+        QTime time;
+        time.setHMS(mHour,mMinute,mSec,mMSec);
+        pdt->setDate(dt);
+        pdt->setTime(time);
+
+    }
+};
+
+class procsm : public QObject
+{
+#ifdef USEDBUS
+    Q_OBJECT
+
+#endif
+public:
+    procsm(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode);
+    int writemsg(const char * str,const unsigned int nSize);
+    unsigned int getcurrentnext();
+    int readmsg(unsigned int index,char * str,unsigned int nMaxSize,unsigned int * nRead,QDateTime * pdt);
+
+    bool AttachMem();
+
+private:
+    int MoveMem(const unsigned int nSize);
+    QSharedMemory * mpASM;
+    unsigned int mnBufSize;
+    unsigned int mnMaxPacCount;
+    procsm_info * mpinfo;
+    procsm_head * mphead;
+
+    bool mbAttach;
+
+    char * mstrtem;
+
+public:
+    const static int ModeRead = 1;
+    const static int ModeWrite = 0;
+
+    iv::modulemsg_type mmodulemsg_type;
+
+#ifdef USEDBUS
+private slots:
+    void onQuery();
+
+#endif
+private:
+#ifdef USEDBUS
+    QDBusMessage mmsg;
+    QDBusMessage mmsgres;  //Response Message Query;
+
+#endif
+
+
+
+};
+
+#endif // PROCSM_H

+ 310 - 0
src1/common/modulecomm_shm/procsm_if.cpp

@@ -0,0 +1,310 @@
+#include "procsm_if.h"
+#include <QTimer>
+
+#include <iostream>
+
+
+
+procsm_if_readthread::procsm_if_readthread(procsm *pPSM,SMCallBack pCall,const char * strsmname)
+{
+    mpPSM = pPSM;
+    mpCall = pCall;
+    strncpy(mstrsmname,strsmname,255);
+
+#ifdef USEDBUS
+    bool bconnect = QDBusConnection::sessionBus().connect(QString(),"/catarc/adc",  "adc.adciv.modulecomm", strsmname,this,SLOT(onNewMsg(int)));
+    if(bconnect == false)
+    {
+        std::cout<<"procsm_if_readthread::procsm_if_readthread bconect is false"<<std::endl;
+    }
+#endif
+}
+
+procsm_if_readthread::procsm_if_readthread(procsm *pPSM,ModuleFun xFun,const char * strsmname)
+{
+    mpPSM = pPSM;
+    mFun = xFun;
+    strncpy(mstrsmname,strsmname,255);
+    mbFunPlus = true;
+
+#ifdef USEDBUS
+    bool bconnect = QDBusConnection::sessionBus().connect(QString(),"/catarc/adc",  "adc.adciv.modulecomm", strsmname,this,SLOT(onNewMsg(int)));
+    if(bconnect == false)
+    {
+        std::cout<<"procsm_if_readthread::procsm_if_readthread bconect is false"<<std::endl;
+        mbDBUSOK = false;
+        QTimer * timer = new QTimer();
+        timer->setTimerType(Qt::PreciseTimer);
+        delete timer;
+    }
+#endif
+}
+
+
+#ifdef USELCM
+    void procsm_if_readthread::handlerMethod(const lcm::ReceiveBuffer *rbuf, const std::string &channel)
+    {
+        qDebug("lcm receiv data. ");
+        mxindex++;
+        QDateTime dt = QDateTime::currentDateTime();
+        if(mbFunPlus)
+        {
+            mFun((char *)rbuf->data,rbuf->data_size,mxindex,&dt,mstrsmname);
+        }
+        else
+        {
+           (*mpCall)((char *)rbuf->data,rbuf->data_size,mxindex,&dt,mstrsmname);
+        }
+    }
+#endif
+
+
+void procsm_if_readthread::puaseread()
+{
+    mbRun = false;
+}
+
+void procsm_if_readthread::continueread()
+{
+    mbRun = true;
+}
+
+void procsm_if_readthread::run()
+{
+#ifdef USELCM
+    mlcm.subscribe(mstrsmname,&procsm_if_readthread::handlerMethod,this);
+    while(!QThread::isInterruptionRequested())
+    {
+        mlcm.handle();
+    }
+    return;
+#endif
+    QTime xTime;
+    xTime.start();
+    unsigned int nBufLen = 1;
+    unsigned int nRead;
+    char * str = new char[nBufLen];
+    unsigned int index =0;
+
+
+    QDateTime *pdt = new QDateTime();
+
+    bool bAttach = false;
+    while(!QThread::isInterruptionRequested())
+    {
+        if(mbRun == false)
+        {
+            msleep(10);
+            continue;
+        }
+        if(bAttach == false)
+        {
+            bAttach = mpPSM->AttachMem();
+            if(bAttach == false)
+            {
+                msleep(1);
+                continue;
+            }
+            else
+            {
+                index = mpPSM->getcurrentnext();
+            }
+        }
+
+        int nRtn = mpPSM->readmsg(index,str,nBufLen,&nRead,pdt);
+        if(nRtn == 0)
+        {
+#ifdef USEDBUS
+            if(mbDBUSOK == true)
+            {
+                mWaitMutex.lock();
+                mwc.wait(&mWaitMutex,10);
+                mWaitMutex.unlock();
+            }
+            else
+            {
+                msleep(1);
+            }
+#else
+            msleep(1);
+#endif
+        }
+        else
+        {
+            if(nRtn == -1)
+            {
+                nBufLen = nRead;
+                delete str;
+                if(nBufLen < 1)nBufLen = 1;
+                str = new char[nBufLen];
+            }
+            else
+            {
+                if(nRtn == -2)
+                {
+                   index = mpPSM->getcurrentnext();
+                }
+                else
+                {
+                   if(nRtn >0)
+                   {
+                       if(mbFunPlus)
+                       {
+                           mFun(str,nRtn,index,pdt,mstrsmname);
+                       }
+                       else
+                       {
+                          (*mpCall)(str,nRtn,index,pdt,mstrsmname);
+                       }
+                       index++;
+                   }
+                   else
+                   {
+                       usleep(100);
+                   }
+                }
+            }
+        }
+
+    }
+    delete str;
+    delete pdt;
+//    qDebug("Thread finish.");
+}
+
+#ifdef USEDBUS
+
+void procsm_if_readthread::onNewMsg(int x)
+{
+    if(x == 100)std::cout<<x<<std::endl;
+    mwc.wakeAll();
+//    qDebug("wake");
+}
+
+#endif
+
+procsm_if::procsm_if(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode)
+{
+    strncpy(mstrsmname,strsmname,255);
+#ifdef USELCM
+    if(nMode == procsm::ModeWrite)
+    {
+
+    }
+    else
+    {
+
+    }
+    return;
+#endif
+    mpPSM = new procsm(strsmname,nBufSize,nMaxPacCount,nMode);
+    mnType = nMode;
+
+    mTimer.setTimerType(Qt::PreciseTimer);
+
+}
+
+procsm_if::~procsm_if()
+{
+    if(mnType == procsm::ModeRead)
+    {
+
+        mpReadThread->requestInterruption();
+        while(!mpReadThread->isFinished())
+        {
+
+        }
+        delete mpReadThread;
+    }
+    delete mpPSM;
+}
+
+
+
+int procsm_if::writemsg(const char *str, const unsigned int nSize)
+{
+    if(mbRun == false)return -2;
+#ifdef USELCM
+    int nres = mlcm.publish(mstrsmname,str,nSize);
+    qDebug("publish message. res = %d",nres);
+    return 0;
+#endif
+    if(mnType == procsm::ModeRead)return -1; //this is listen.
+    return mpPSM->writemsg(str,nSize);
+}
+
+#ifdef USELCM
+    void procsm_if::handlerMethod(const lcm::ReceiveBuffer *rbuf, const std::string &channel)
+    {
+        qDebug("receiv data. ");
+    }
+#endif
+int procsm_if::listenmsg(SMCallBack pCall)
+{
+//#ifdef USELCM
+////     mlcm.subscribe(mstrsmname,&handlerMethod2);
+//    mlcm.subscribe(mstrsmname,&procsm_if::handlerMethod,this);
+//    while(true)
+//    {
+//        mlcm.handle();
+//    }
+//    return 0;
+//#endif
+    if(mnType == procsm::ModeWrite)return -1; //listening.
+    mpReadThread = new procsm_if_readthread(mpPSM,pCall,mstrsmname);
+//    mpReadThread->setPriority(QThread::TimeCriticalPriority);
+//    mpReadThread->start();
+    mpReadThread->start(QThread::HighestPriority);
+//    mnType = 1;
+    return 0;
+}
+
+int procsm_if::listenmsg(ModuleFun xFun)
+{
+//#ifdef USELCM
+//    mlcm.subscribe(mstrsmname,&procsm_if::handlerMethod,this);
+//    while(true)
+//    {
+//        mlcm.handle();
+//    }
+//    return 0;
+//#endif
+    if(mnType == procsm::ModeWrite)return -1; //listening.
+    mpReadThread = new procsm_if_readthread(mpPSM,xFun,mstrsmname);
+//    mpReadThread->setPriority(QThread::TimeCriticalPriority);
+//    mpReadThread->start();
+    mpReadThread->start(QThread::HighestPriority);
+//    mnType = 1;
+    return 0;
+}
+
+void procsm_if::stoplisten()
+{
+    if(mnType != 1)return;
+    mpReadThread->requestInterruption();
+    while(!mpReadThread->isFinished());
+    mnType = 0;
+//    mpReadThread->deleteLater();
+    qDebug("stop listen ok");
+}
+
+void procsm_if::pausecomm()
+{
+    mbRun = false;
+    if(mnType == procsm::ModeRead)
+    {
+        mpReadThread->puaseread();
+    }
+}
+
+void procsm_if::continuecomm()
+{
+    mbRun = true;
+    if(mnType == procsm::ModeRead)
+    {
+        mpReadThread->continueread();
+    }
+}
+
+
+

+ 99 - 0
src1/common/modulecomm_shm/procsm_if.h

@@ -0,0 +1,99 @@
+#ifndef PROCSM_IF_H
+#define PROCSM_IF_H
+
+#include <QThread>
+#include <QTimer>
+#include <QWaitCondition>
+#include <QMutex>
+#include <functional>
+
+#ifdef USEDBUS
+#include <QtDBus/QDBusMessage>
+#include <QtDBus/QDBusConnection>
+
+#endif
+
+#include "procsm.h"
+
+typedef void (* SMCallBack)(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname);
+using namespace std::placeholders;
+typedef std::function<void(const char * ,const unsigned int , const unsigned int , QDateTime * ,const char *)> ModuleFun;
+
+class procsm_if_readthread:public QThread
+{
+    Q_OBJECT
+public:
+#ifdef USELCM
+
+#endif
+    procsm_if_readthread(procsm * pPSM,SMCallBack pCall,const char * strsmname);
+    procsm_if_readthread(procsm * pPSM,ModuleFun xFun,const char * strsmname);
+
+    void puaseread();
+    void continueread();
+private slots:
+#ifdef USEDBUS
+    void onNewMsg(int x);
+#endif
+private:
+
+#ifdef USELCM
+    lcm::LCM mlcm;
+    void handlerMethod(const lcm::ReceiveBuffer *rbuf,const std::string &channel);
+    int mxindex = 0;
+#endif
+    void run();
+    procsm * mpPSM;
+    SMCallBack  mpCall;
+    ModuleFun mFun;
+    char mstrsmname[256];
+
+    QWaitCondition mwc;
+
+    QMutex mWaitMutex;
+    bool mbFunPlus = false;
+    bool mbRun = true;
+    bool mbDBUSOK = true;
+};
+
+class procsm_if
+{
+
+
+public:
+    procsm_if(const char * strsmname,const unsigned int nBufSize,const unsigned int nMaxPacCount,const int nMode);
+    ~procsm_if();
+
+    int writemsg(const char * str,const unsigned int nSize);
+    int listenmsg(SMCallBack pCall);
+    int listenmsg(ModuleFun xFun);
+    void stoplisten();
+
+    void pausecomm();
+    void continuecomm();
+
+
+private:
+    procsm * mpPSM;
+    int mnType;
+    procsm_if_readthread * mpReadThread;
+    QTimer mTimer;
+    char mstrsmname[256];
+
+    bool mbRun = true;
+
+
+
+#ifdef USELCM
+    lcm::LCM mlcm;
+    void handlerMethod(const lcm::ReceiveBuffer *rbuf,const std::string &channel);
+#endif
+
+
+
+
+
+
+};
+
+#endif // PROCSM_IF_H

+ 73 - 0
src1/driver/driver_lidar_rs16/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 61 - 0
src1/driver/driver_lidar_rs16/driver_lidar_rs16.pro

@@ -0,0 +1,61 @@
+QT -= gui
+
+QT += network
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        ../../interface/ivmodule.cpp \
+        ../interface/ivdriver.cpp \
+        ../interface/ivdriver_lidar.cpp \
+        ../interface/lidarmain.cpp \
+        ivdriver_lidar_rs16.cpp \
+        main.cpp
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+HEADERS += \
+    ../../interface/ivmodule.h \
+    ../interface/ivdriver.h \
+    ../interface/ivdriver_lidar.h \
+    ../interface/lidarmain.h \
+    ivdriver_lidar_rs16.h
+
+!include(../../../include/ivpcl.pri ) {
+    error( "Couldn't find the ivpcl.pri file!" )
+}
+
+!include(../../../include/ivyaml-cpp.pri ) {
+    error( "Couldn't find the ivyaml-cpp.pri file!" )
+}
+
+
+INCLUDEPATH += $$PWD/../interface
+INCLUDEPATH += $$PWD/../../interface
+
+
+INCLUDEPATH += $$PWD/../../common/modulecomm
+
+INCLUDEPATH += $$PWD/../../common/modulecomm_shm
+INCLUDEPATH += $$PWD/../../common/modulecomm_fastrtps
+INCLUDEPATH += $$PWD/../../common/modulecomm_inter
+
+LIBS += -L$$PWD/../../common/build-modulecomm-Debug -lmodulecomm
+LIBS += -L$$PWD/../../common/build-modulecomm_fastrtps-Debug -lmodulecomm_fastrtps
+LIBS += -L$$PWD/../../common/build-modulecomm_shm-Debug -lmodulecomm_shm
+LIBS += -L$$PWD/../../common/build-modulecomm_inter-Debug -lmodulecomm_inter

+ 139 - 0
src1/driver/driver_lidar_rs16/ivdriver_lidar_rs16.cpp

@@ -0,0 +1,139 @@
+#include "ivdriver_lidar_rs16.h"
+
+namespace iv {
+
+
+ivdriver_lidar_rs16::ivdriver_lidar_rs16()
+{
+
+}
+
+int ivdriver_lidar_rs16::processudpData(QByteArray ba, pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud)
+{
+    static double fAngle_Total = 0;
+    static double fAngle_Last = 0;
+
+    int nrtn = 0;
+
+    float Ang = 0;
+    float Range = 0;
+    int Group = 0;
+    int pointi = 0;
+    float wt = 0;
+    int wt1 = 0;
+
+    float V_theta[16] = {-15,-13,-11,-9,-7,-5,-3,-1,15,13,11,9,7,5,3,1};
+
+    char * pstr = ba.data();
+
+    wt1 = ((pstr[2 + Group * 100] *256) + pstr[ 3 + Group * 100]) ;
+    wt = wt1/ 100.0;
+
+    double fAngX = wt;
+    if(fabs(fAngX-fAngle_Last)>300)
+    {
+        fAngle_Total = fAngle_Total + fabs(fabs(fAngX-fAngle_Last)-360);
+    }
+    else
+    {
+        fAngle_Total = fAngle_Total + fabs(fabs(fAngX-fAngle_Last));
+    }
+
+    fAngle_Last = fAngX;
+    if(fAngle_Total > 360)
+    {
+        nrtn = 1;
+        fAngle_Total = 0;
+    }
+
+
+    for (Group = 0; Group <= 11; Group++)
+    {
+        wt1 = ((pstr[2 + Group * 100] *256) + pstr[ 3 + Group * 100]) ;
+        wt = wt1/ 100.0;
+
+
+        for (pointi = 0; pointi <16; pointi++)
+        {
+//                        Ang = (0 - wt - w * T[pointi] - H_BETA[pointi]+213) / 180.0 * Lidar_Pi;
+            Ang = (0 - wt) / 180.0 * M_PI;
+            Range = ((pstr[ Group * 100 + 4 + 3 * pointi] << 8) + pstr[Group * 100 + 5 + 3 * pointi]);
+            unsigned char intensity = pstr[ Group * 100 + 6 + 3 * pointi];
+            Range=Range* 5.0/1000.0;
+
+            if(Range<150)
+            {
+                pcl::PointXYZI point;
+                point.x  = Range*cos(V_theta[pointi] / 180 * M_PI)*cos(Ang + mfrollang);
+                point.y  = Range*cos(V_theta[pointi] / 180 * M_PI)*sin(Ang + mfrollang);
+                point.z  = Range*sin(V_theta[pointi] / 180 * M_PI);
+                if(mbinclix)
+                {
+                    double y,z;
+                    y = point.y;
+                    z = point.z;
+                    point.y = y*mcos_finclinationang_xaxis +z*msin_finclinationang_xaxis;
+                    point.z = z*mcos_finclinationang_xaxis - y*msin_finclinationang_xaxis;
+                }
+                if(mbincliy)
+                {
+                    double z,x;
+                    z = point.z;
+                    x = point.x;
+                    point.z = z*mcos_finclinationang_yaxis + x*msin_finclinationang_yaxis;
+                    point.x = x*mcos_finclinationang_yaxis - z*msin_finclinationang_yaxis;
+                }
+                point.intensity = intensity;
+                point_cloud->points.push_back(point);
+
+
+                ++point_cloud->width;
+            }
+        }
+
+
+        wt = wt + 0.18;
+
+
+
+        for (pointi = 0; pointi < 16; pointi++)
+        {
+            Ang = (0 - wt) / 180.0 * M_PI;
+   //         Ang = Ang+angdiff;
+            Range = ((pstr[ Group * 100 + 52 + 3 * pointi] << 8) + pstr[Group * 100 + 53 + 3 * pointi]);
+            unsigned char intensity = pstr[ Group * 100 + 54 + 3 * pointi];
+            Range=Range* 5.0/1000.0;
+
+            if(Range<150)
+            {
+                pcl::PointXYZI point;
+                point.x  = Range*cos(V_theta[pointi] / 180 * M_PI)*cos(Ang + mfrollang);
+                point.y  = Range*cos(V_theta[pointi] / 180 * M_PI)*sin(Ang + mfrollang);
+                point.z  = Range*sin(V_theta[pointi] / 180 * M_PI);
+                if(mbinclix)
+                {
+                    double y,z;
+                    y = point.y;z = point.z;
+                    point.y = y*mcos_finclinationang_xaxis +z*msin_finclinationang_xaxis;
+                    point.z = z*mcos_finclinationang_xaxis - y*msin_finclinationang_xaxis;
+                }
+                if(mbincliy)
+                {
+                    double z,x;
+                    z = point.z;x = point.x;
+                    point.z = z*mcos_finclinationang_yaxis + x*msin_finclinationang_yaxis;
+                    point.x = x*mcos_finclinationang_yaxis - z*msin_finclinationang_yaxis;
+                }
+                point.intensity = intensity;
+                point_cloud->points.push_back(point);
+
+
+                ++point_cloud->width;
+            }
+        }
+    }
+    return nrtn;
+
+}
+
+}

+ 20 - 0
src1/driver/driver_lidar_rs16/ivdriver_lidar_rs16.h

@@ -0,0 +1,20 @@
+#ifndef IVDRIVER_LIDAR_RS16_H
+#define IVDRIVER_LIDAR_RS16_H
+
+#include "ivdriver_lidar.h"
+
+namespace iv {
+
+
+class ivdriver_lidar_rs16 : public ivdriver_lidar
+{
+public:
+    ivdriver_lidar_rs16();
+    virtual int processudpData(QByteArray ba,pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud);
+
+
+};
+
+}
+
+#endif // IVDRIVER_LIDAR_RS16_H

+ 19 - 0
src1/driver/driver_lidar_rs16/main.cpp

@@ -0,0 +1,19 @@
+#include <QCoreApplication>
+
+#include "lidarmain.h"
+
+#include "ivdriver_lidar_rs16.h"
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    iv::ivdriver_lidar * pivm = new iv::ivdriver_lidar_rs16();
+    int nrtn = lidarmain(pivm,argc,argv,&a,"driver_lidar_rs16");
+
+    if(nrtn == 0)
+    {
+        return 0;
+    }
+    return a.exec();
+}

+ 10 - 0
src1/driver/interface/ivdriver.cpp

@@ -0,0 +1,10 @@
+#include "ivdriver.h"
+
+namespace iv {
+
+ivdriver::ivdriver()
+{
+
+}
+
+}

+ 16 - 0
src1/driver/interface/ivdriver.h

@@ -0,0 +1,16 @@
+#ifndef IVDRIVER_H
+#define IVDRIVER_H
+
+#include "ivmodule.h"
+
+namespace  iv {
+
+class ivdriver : public ivmodule
+{
+public:
+    ivdriver();
+};
+
+}
+
+#endif // IVDRIVER_H

+ 141 - 0
src1/driver/interface/ivdriver_lidar.cpp

@@ -0,0 +1,141 @@
+#include "ivdriver_lidar.h"
+
+#include <iostream>
+
+namespace  iv {
+ivdriver_lidar::ivdriver_lidar()
+{
+    strncpy(mstr_hostip,"0.0.0.0",256);
+    strncpy(mstr_port,"6699",256);
+    strncpy(mstr_memname,"lidar_pc",256);
+}
+
+void ivdriver_lidar::RegisterPointMsg(const char * strmemname,iv::modulecomm::ModuleComm_TYPE xtype)
+{
+    mpa = iv::modulecomm::RegisterSend(strmemname,10000000,1,xtype);
+}
+
+
+
+void ivdriver_lidar::SharePointCloud(pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud)
+{
+    char * strOut = new char[4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI)];
+
+    int * pHeadSize = (int *)strOut;
+    *pHeadSize = 4 + point_cloud->header.frame_id.size()+4+8;
+    memcpy(strOut+4,point_cloud->header.frame_id.c_str(),point_cloud->header.frame_id.size());
+    pcl::uint32_t * pu32 = (pcl::uint32_t *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
+    *pu32 = point_cloud->header.seq;
+    memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
+    pcl::PointXYZI * p;
+    p = (pcl::PointXYZI *)(strOut +4+sizeof(point_cloud->header.frame_id.size()) + 4+8 );
+    memcpy(p,point_cloud->points.data(),point_cloud->width * sizeof(pcl::PointXYZI));
+
+    iv::modulecomm::ModuleSendMsg(mpa,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->width * sizeof(pcl::PointXYZI));
+    delete strOut;
+}
+
+
+void ivdriver_lidar::modulerun()
+{
+
+    if(mfinclinationang_xaxis != 0.0)mbinclix = true;
+    if(mfinclinationang_yaxis != 0.0)mbincliy = true;
+    mcos_finclinationang_xaxis= cos(mfinclinationang_xaxis);
+    msin_finclinationang_xaxis = sin(mfinclinationang_xaxis);
+    mcos_finclinationang_yaxis = cos(mfinclinationang_yaxis);
+    msin_finclinationang_yaxis = sin(mfinclinationang_yaxis);
+
+    RegisterPointMsg(mstr_memname,getdefefaultcommtype());
+
+    mbrunudpthread = true;
+    std::thread * xudpthread = new std::thread(&ivdriver_lidar::threadudp,this);
+
+    QDateTime dt = QDateTime::currentDateTime();
+    pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
+                new pcl::PointCloud<pcl::PointXYZI>());
+
+    point_cloud->header.frame_id = "velodyne";
+    point_cloud->height = 1;
+    point_cloud->header.stamp = dt.currentMSecsSinceEpoch();
+    point_cloud->width = 0;
+    point_cloud->header.seq =m_seq;
+    m_seq++;
+
+    while(mbrun)
+    {
+        if(mvectorba.size()>0)
+        {
+            mMutexba.lock();
+            QByteArray ba = mvectorba[0];
+            mvectorba.erase(mvectorba.begin());
+            mMutexba.unlock();
+            if(processudpData(ba,point_cloud) == 1)
+            {
+                SharePointCloud(point_cloud);
+                point_cloud->clear();
+                point_cloud->height = 1;
+                point_cloud->header.stamp = dt.currentMSecsSinceEpoch();
+                point_cloud->width = 0;
+                point_cloud->header.seq =m_seq;
+                m_seq++;
+            }
+        }
+        else
+        {
+            std::this_thread::sleep_for(std::chrono::milliseconds(1));
+        }
+    }
+
+    mbrunudpthread = false;
+    xudpthread->join();
+
+
+}
+
+void ivdriver_lidar::threadudp()
+{
+    QUdpSocket * udpSocket = new QUdpSocket( );
+    bool bbind =     udpSocket->bind(QHostAddress(mstr_hostip), atoi(mstr_port));
+    if(bbind == false)
+    {
+        qDebug("bind socket %s:%s error.",mstr_hostip,mstr_port);
+        return;
+    }
+    int nnotrecv = 0;
+    while(mbrunudpthread)
+    {
+        if(udpSocket->hasPendingDatagrams())
+        {
+            if(nnotrecv > 10000)
+            {
+                std::cout<<" Recv Data."<<std::endl;
+            }
+            QNetworkDatagram datagram = udpSocket->receiveDatagram();
+            mMutexba.lock();
+            if(mvectorba.size()<1000)
+            {
+                mvectorba.push_back(datagram.data());
+            }
+            else
+            {
+                std::cout<<" proc buffer is full."<<std::endl;
+            }
+            mMutexba.unlock();
+            datagram.clear();
+            nnotrecv = 0;
+        }
+        else
+        {
+            nnotrecv++;
+//            std::cout<<"running."<<std::endl;
+            std::this_thread::sleep_for(std::chrono::microseconds(100));
+            if(nnotrecv == 10000)
+            {
+                std::cout<<"not recv datagram."<<std::endl;
+            }
+        }
+    }
+}
+
+}

+ 64 - 0
src1/driver/interface/ivdriver_lidar.h

@@ -0,0 +1,64 @@
+#ifndef IVDRIVER_LIDAR_H
+#define IVDRIVER_LIDAR_H
+
+#include <QUdpSocket>
+#include <QNetworkDatagram>
+#include <vector>
+#include <QMutex>
+
+#include <pcl/point_cloud.h>
+#include <pcl/point_types.h>
+
+#include "ivdriver.h"
+
+#include "modulecomm.h"
+
+namespace  iv {
+
+
+class ivdriver_lidar : public ivdriver
+{
+public:
+    ivdriver_lidar();
+
+    void RegisterPointMsg(const char * strmemname,iv::modulecomm::ModuleComm_TYPE xtype);
+    void SharePointCloud(pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud);
+    virtual void modulerun();
+    virtual int processudpData(QByteArray ba,pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud) = 0;
+
+private:
+    void * mpa;
+    pcl::PointCloud<pcl::PointXYZI>::Ptr mpoint_cloud;
+    qint64 m_seq = 0;
+public:
+    char mstr_memname[256];
+    double mfrollang = 0;
+    double  mfinclinationang_yaxis = 0;  //from y axis
+    double mfinclinationang_xaxis = 0;  //from x axis
+    char mstr_hostip[256];
+    char mstr_port[256];
+    double mfoffset_x = 0;
+    double mfoffset_y = 0;
+    double mfoffset_z = 0;
+
+    bool mbinclix = false;
+    bool mbincliy = false;
+ //   if(finclinationang_xaxis != 0.0)binclix = true;
+ //   if(finclinationang_yaxis != 0.0)bincliy = true;
+
+    double mcos_finclinationang_xaxis;// = cos(mfinclinationang_xaxis);
+    double msin_finclinationang_xaxis;// = sin(mfinclinationang_xaxis);
+    double mcos_finclinationang_yaxis;// = cos(mfinclinationang_yaxis);
+    double msin_finclinationang_yaxis;// = sin(mfinclinationang_yaxis);
+
+private:
+    void threadudp();
+    bool mbrunudpthread = false;
+    std::vector<QByteArray> mvectorba;
+    QMutex mMutexba;
+
+};
+
+}
+
+#endif // IVDRIVER_LIDAR_H

+ 220 - 0
src1/driver/interface/lidarmain.cpp

@@ -0,0 +1,220 @@
+#include <QCoreApplication>
+
+
+#include "ivdriver_lidar_rs16.h"
+
+#include <signal.h>
+
+#include <getopt.h>
+#include <iostream>
+
+#include <iostream>
+#include <fstream>
+#include <yaml-cpp/yaml.h>
+
+iv::ivmodule * gpivmodule;
+QCoreApplication * gpapp;
+
+void sigint_handler(int sig){
+    if(sig == SIGINT){
+        // ctrl+c退出时执行的代码
+        delete gpivmodule;
+        gpapp->exit(0);
+    }
+}
+char gstr_memname[256];
+char gstr_rollang[256];
+char gstr_inclinationang_yaxis[256];  //from y axis
+char gstr_inclinationang_xaxis[256];  //from x axis
+char gstr_hostip[256];
+char gstr_port[256];
+char gstr_yaml[256];
+
+
+void print_useage()
+{
+    std::cout<<" -m --memname $memname : share memory name. eq.  -m lidar_pc"<<std::endl;
+    std::cout<<" -r --rollang $rollang : roll angle. eq.  -r 10.0"<<std::endl;
+    std::cout<<" -x --inclinationang_xaxis $inclinationang_xaxis : inclination angle from x axis. eq.  -x 0.0"<<std::endl;
+    std::cout<<" -y --inclinationang_yaxis $inclinationang_yaxis : inclination angle from y axis. eq.  -y 0.0"<<std::endl;
+    std::cout<<" -o --hostip $hostip : host ip. eq.  -o 192.168.1.111"<<std::endl;
+    std::cout<<" -p --port $port : port . eq.  -p 2368"<<std::endl;
+    std::cout<<" -s --setyaml $yaml : port . eq.  -s rs1.yaml"<<std::endl;
+    std::cout<<" -h --help print help"<<std::endl;
+}
+
+int  GetOptLong(int argc, char *argv[]) {
+    int nRtn = 0;
+    int opt; // getopt_long() 的返回值
+    int digit_optind = 0; // 设置短参数类型及是否需要参数
+
+    // 如果option_index非空,它指向的变量将记录当前找到参数符合long_opts里的
+    // 第几个元素的描述,即是long_opts的下标值
+    int option_index = 0;
+    // 设置短参数类型及是否需要参数
+    const char *optstring = "m:r:x:y:o:p:s:h";
+
+    // 设置长参数类型及其简写,比如 --reqarg <==>-r
+    /*
+    struct option {
+             const char * name;  // 参数的名称
+             int has_arg; // 是否带参数值,有三种:no_argument, required_argument,optional_argument
+             int * flag; // 为空时,函数直接将 val 的数值从getopt_long的返回值返回出去,
+                     // 当非空时,val的值会被赋到 flag 指向的整型数中,而函数返回值为0
+             int val; // 用于指定函数找到该选项时的返回值,或者当flag非空时指定flag指向的数据的值
+        };
+    其中:
+        no_argument(即0),表明这个长参数不带参数(即不带数值,如:--name)
+            required_argument(即1),表明这个长参数必须带参数(即必须带数值,如:--name Bob)
+            optional_argument(即2),表明这个长参数后面带的参数是可选的,(即--name和--name Bob均可)
+     */
+    static struct option long_options[] = {
+        {"memname", required_argument, NULL, 'm'},
+        {"rollang", required_argument, NULL, 'r'},
+        {"inclinationang_xaxis", required_argument, NULL, 'x'},
+        {"inclinationang_yaxis", required_argument, NULL, 'y'},
+        {"hostip", required_argument, NULL, 'o'},
+        {"port", required_argument, NULL, 'p'},
+        {"setyaml", required_argument, NULL, 's'},
+        {"help",  no_argument,       NULL, 'h'},
+ //       {"optarg", optional_argument, NULL, 'o'},
+        {0, 0, 0, 0}  // 添加 {0, 0, 0, 0} 是为了防止输入空值
+    };
+
+    while ( (opt = getopt_long(argc,
+                               argv,
+                               optstring,
+                               long_options,
+                               &option_index)) != -1) {
+//        printf("opt = %c\n", opt); // 命令参数,亦即 -a -b -n -r
+//        printf("optarg = %s\n", optarg); // 参数内容
+//        printf("optind = %d\n", optind); // 下一个被处理的下标值
+//        printf("argv[optind - 1] = %s\n",  argv[optind - 1]); // 参数内容
+//        printf("option_index = %d\n", option_index);  // 当前打印参数的下标值
+//        printf("\n");
+        switch(opt)
+        {
+        case 'm':
+            strncpy(gstr_memname,optarg,255);
+            break;
+        case 'r':
+            strncpy(gstr_rollang,optarg,255);
+            break;
+        case 'x':
+            strncpy(gstr_inclinationang_xaxis,optarg,255);
+            break;
+        case 'y':
+            strncpy(gstr_inclinationang_yaxis,optarg,255);
+            break;
+        case 'o':
+            strncpy(gstr_hostip,optarg,255);
+            break;
+        case 'p':
+            strncpy(gstr_port,optarg,255);
+            break;
+        case 's':
+            strncpy(gstr_yaml,optarg,255);
+            break;
+        case 'h':
+            print_useage();
+            nRtn = 1; //because use -h
+            break;
+        default:
+            break;
+        }
+
+    }
+
+    return nRtn;
+}
+
+void decodeyaml(const char * stryaml)
+{
+    YAML::Node config;
+    try
+    {
+        config = YAML::LoadFile(stryaml);
+    }
+    catch(YAML::BadFile e)
+    {
+        qDebug("load yaml error.");
+        return;
+    }
+
+
+    if(config["memname"])
+    {
+        strncpy(gstr_memname,config["memname"].as<std::string>().data(),255);
+    }
+    if(config["rollang"])
+    {
+        strncpy(gstr_rollang,config["rollang"].as<std::string>().data(),255);
+    }
+    if(config["inclinationang_xaxis"])
+    {
+        strncpy(gstr_inclinationang_xaxis,config["inclinationang_xaxis"].as<std::string>().data(),255);
+    }
+    if(config["inclinationang_yaxis"])
+    {
+        strncpy(gstr_inclinationang_yaxis,config["inclinationang_yaxis"].as<std::string>().data(),255);
+    }
+    if(config["hostip"])
+    {
+        strncpy(gstr_hostip,config["hostip"].as<std::string>().data(),255);
+    }
+    if(config["port"])
+    {
+        strncpy(gstr_port,config["port"].as<std::string>().data(),255);
+    }
+
+
+
+//    std::cout<<gstr_memname<<std::endl;
+//    std::cout<<gstr_rollang<<std::endl;
+//    std::cout<<gstr_inclinationang_xaxis<<std::endl;
+//    std::cout<<gstr_inclinationang_yaxis<<std::endl;
+//    std::cout<<gstr_hostip<<std::endl;
+//    std::cout<<gstr_port<<std::endl;
+}
+
+
+
+int lidarmain(iv::ivdriver_lidar * pivm,int argc, char *argv[],QCoreApplication * pa,const char * strmodulename)
+{
+
+    snprintf(gstr_memname,255,"lidar_pc");
+    snprintf(gstr_rollang,255,"-9.0");
+    snprintf(gstr_inclinationang_xaxis,255,"0.0");
+    snprintf(gstr_inclinationang_yaxis,255,"0");
+    snprintf(gstr_hostip,255,"0.0.0.0");
+    snprintf(gstr_port,255,"6699");//默认端口号
+    snprintf(gstr_yaml,255,"");
+
+    int nRtn = GetOptLong(argc,argv);
+    if(nRtn == 1)  //show help,so exit.
+    {
+        return 0;
+    }
+
+    if(strnlen(gstr_yaml,255)>0)
+    {
+        decodeyaml(gstr_yaml);
+    }
+
+    strncpy(pivm->mstr_memname,gstr_memname,256);
+    strncpy(pivm->mstr_hostip,gstr_hostip,256);
+    strncpy(pivm->mstr_port,gstr_port,256);
+    pivm->mfrollang = atof(gstr_rollang)*M_PI/180.0;
+    pivm->mfinclinationang_xaxis = atof(gstr_inclinationang_xaxis)*M_PI/180.0;
+    pivm->mfinclinationang_yaxis = atof(gstr_inclinationang_yaxis)*M_PI/180.0;
+
+    iv::ivmodule * pivmodule = pivm;
+    signal(SIGINT, sigint_handler);
+    gpivmodule = pivmodule;
+    pivmodule->start();
+    gpapp = pa;
+
+    return 1;
+
+
+}

+ 8 - 0
src1/driver/interface/lidarmain.h

@@ -0,0 +1,8 @@
+#ifndef LIDARMAIN_H
+#define LIDARMAIN_H
+
+#include "ivmodule.h"
+#include "ivdriver_lidar.h"
+
+int lidarmain(iv::ivdriver_lidar * pivm,int argc, char *argv[],QCoreApplication * pa,const char * strmodulename);
+#endif // LIDARMAIN_H

+ 45 - 0
src1/interface/ivmodule.cpp

@@ -0,0 +1,45 @@
+#include "ivmodule.h"
+
+#include <string.h>
+
+namespace iv {
+
+
+ivmodule::ivmodule()
+{
+
+}
+
+ivmodule::~ivmodule()
+{
+    mbrun = false;
+    mpthread->join();
+}
+
+void ivmodule::start()
+{
+    mbrun = true;
+    mpthread = new std::thread(&ivmodule::modulerun,this);
+}
+
+void ivmodule::modulerun()
+{
+
+}
+
+void ivmodule::setmodulename(const char *strmodulename)
+{
+    strncpy(mstrmodulename,strmodulename,256);
+}
+
+void ivmodule::setdefaultcommtype(iv::modulecomm::ModuleComm_TYPE xtype)
+{
+    mdefcommtype = xtype;
+}
+
+iv::modulecomm::ModuleComm_TYPE ivmodule::getdefefaultcommtype()
+{
+    return mdefcommtype;
+}
+
+}

+ 31 - 0
src1/interface/ivmodule.h

@@ -0,0 +1,31 @@
+#ifndef IVMODULE_H
+#define IVMODULE_H
+
+#include <thread>
+
+#include "modulecomm.h"
+
+namespace  iv {
+
+class ivmodule
+{
+public:
+    ivmodule();
+    ~ivmodule();
+
+public:
+    void start();
+    virtual void modulerun();
+    void setmodulename(const char * strmodulename);
+    void setdefaultcommtype(iv::modulecomm::ModuleComm_TYPE xtype);
+    iv::modulecomm::ModuleComm_TYPE getdefefaultcommtype();
+public:
+    bool mbrun = false;
+private:
+    std::thread * mpthread;
+    iv::modulecomm::ModuleComm_TYPE mdefcommtype = iv::modulecomm::ModuleComm_SHAREMEM;
+    char mstrmodulename[256];
+};
+}
+
+#endif // IVMODULE_H

+ 73 - 0
src1/test/testmodulecomm_inter/.gitignore

@@ -0,0 +1,73 @@
+# This file is used to ignore files which are generated
+# ----------------------------------------------------------------------------
+
+*~
+*.autosave
+*.a
+*.core
+*.moc
+*.o
+*.obj
+*.orig
+*.rej
+*.so
+*.so.*
+*_pch.h.cpp
+*_resource.rc
+*.qm
+.#*
+*.*#
+core
+!core/
+tags
+.DS_Store
+.directory
+*.debug
+Makefile*
+*.prl
+*.app
+moc_*.cpp
+ui_*.h
+qrc_*.cpp
+Thumbs.db
+*.res
+*.rc
+/.qmake.cache
+/.qmake.stash
+
+# qtcreator generated files
+*.pro.user*
+
+# xemacs temporary files
+*.flc
+
+# Vim temporary files
+.*.swp
+
+# Visual Studio generated files
+*.ib_pdb_index
+*.idb
+*.ilk
+*.pdb
+*.sln
+*.suo
+*.vcproj
+*vcproj.*.*.user
+*.ncb
+*.sdf
+*.opensdf
+*.vcxproj
+*vcxproj.*
+
+# MinGW generated files
+*.Debug
+*.Release
+
+# Python byte code
+*.pyc
+
+# Binaries
+# --------
+*.dll
+*.exe
+

+ 42 - 0
src1/test/testmodulecomm_inter/main.cpp

@@ -0,0 +1,42 @@
+#include <QCoreApplication>
+
+#include <thread>
+
+#include "modulecomm.h"
+
+void * gpa;
+
+std::chrono::time_point<std::chrono::steady_clock, std::chrono::duration<double,std::nano>> t1,t2;
+
+void testcall(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+    qint64 sendtime;
+    t2 = std::chrono::steady_clock::now();
+    double dr_ns = std::chrono::duration<double,std::nano>(t2-t1).count();
+    memcpy(&sendtime,strdata,8);
+    qDebug("lat is %d ns is %f ",QDateTime::currentMSecsSinceEpoch() - sendtime,dr_ns);
+}
+
+void threadsend()
+{
+    char * strdata = new char[3000000];
+    while(1)
+    {
+        std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+        qint64 ntime = QDateTime::currentMSecsSinceEpoch();
+        memcpy(strdata,&ntime,8);
+        iv::modulecomm::ModuleSendMsg(gpa,strdata,2000000);
+        t1 =  std::chrono::steady_clock::now();
+        qDebug("send msg.");
+    }
+}
+
+int main(int argc, char *argv[])
+{
+    QCoreApplication a(argc, argv);
+
+    gpa = iv::modulecomm::RegisterSend("test1",3000000,1,iv::modulecomm::ModuleComm_INTERIOR);
+    iv::modulecomm::RegisterRecv("test1",testcall,iv::modulecomm::ModuleComm_INTERIOR);
+    std::thread * xthread = new std::thread(threadsend);
+    return a.exec();
+}

+ 35 - 0
src1/test/testmodulecomm_inter/testmodulecomm_inter.pro

@@ -0,0 +1,35 @@
+QT -= gui
+
+CONFIG += c++11 console
+CONFIG -= app_bundle
+
+# The following define makes your compiler emit warnings if you use
+# any Qt feature that has been marked deprecated (the exact warnings
+# depend on your compiler). Please consult the documentation of the
+# deprecated API in order to know how to port your code away from it.
+DEFINES += QT_DEPRECATED_WARNINGS
+
+# You can also make your code fail to compile if it uses deprecated APIs.
+# In order to do so, uncomment the following line.
+# You can also select to disable deprecated APIs only up to a certain version of Qt.
+#DEFINES += QT_DISABLE_DEPRECATED_BEFORE=0x060000    # disables all the APIs deprecated before Qt 6.0.0
+
+SOURCES += \
+        main.cpp
+
+# Default rules for deployment.
+qnx: target.path = /tmp/$${TARGET}/bin
+else: unix:!android: target.path = /opt/$${TARGET}/bin
+!isEmpty(target.path): INSTALLS += target
+
+INCLUDEPATH += $$PWD/../../common/modulecomm
+
+INCLUDEPATH += $$PWD/../../common/modulecomm_shm
+INCLUDEPATH += $$PWD/../../common/modulecomm_fastrtps
+INCLUDEPATH += $$PWD/../../common/modulecomm_inter
+
+LIBS += -L$$PWD/../../common/build-modulecomm-Debug -lmodulecomm
+LIBS += -L$$PWD/../../common/build-modulecomm_fastrtps-Debug -lmodulecomm_fastrtps
+LIBS += -L$$PWD/../../common/build-modulecomm_shm-Debug -lmodulecomm_shm
+LIBS += -L$$PWD/../../common/build-modulecomm_inter-Debug -lmodulecomm_inter
+