Pārlūkot izejas kodu

change tool_trace2vectormap. add LimVel.

yuchuli 3 gadi atpakaļ
vecāks
revīzija
93296bf5d4

+ 5 - 7
src/ros/catkin/src/pilottoros/src/main.cpp

@@ -90,6 +90,7 @@ void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsign
     pcl::PointXYZI * p;
     p = (pcl::PointXYZI *)((char *)strdata + *pHeadSize);
 
+    // point_cloud->header.frame_id  = "map";
 	point_cloud->resize(nPCount);
 	memcpy(point_cloud->points.data(),p,nPCount*sizeof(pcl::PointXYZI));
 
@@ -166,16 +167,16 @@ void Listenodom(const char * strdata,const unsigned int nSize,const unsigned int
 
 
     geometry_msgs::PoseStamped  xPose;
-    xPose.header.frame_id = "/map";
+    xPose.header.frame_id = "map";
     xPose.pose = msg.pose.pose;
     geometry_msgs::TwistStamped xtwist;
-     xtwist.header.frame_id = "/map";
+    xtwist.header.frame_id = "map";
     xtwist.twist = msg.twist.twist;
 
-std::cout<<" listen odom."<<std::endl;
+//std::cout<<" listen odom."<<std::endl;
 if(_use_pilot_waypoints)
 {
-    std::cout<<" public pose"<<std::endl;
+ //   std::cout<<" public pose"<<std::endl;
     pose_pub.publish(xPose);
     twist_pub.publish(xtwist);
 }
@@ -282,9 +283,6 @@ void ListenWayPointsMap(const char * strdata,const unsigned int nSize,const unsi
 
     if(_use_pilot_waypoints)
     {
-        
-         xlane.header.frame_id = "/map";
-         
         waypoints_pub.publish(xlane);
     }
 

+ 2 - 0
src/tool/tool_trace2vectormap/mainwindow.cpp

@@ -17,6 +17,7 @@ MainWindow::MainWindow(QWidget *parent)
     ui->lineEdit_Lno->setText("3");
     ui->lineEdit_LeftDis->setText("2.3");
     ui->lineEdit_RIghtDis->setText("2.3");
+    ui->lineEdit_VelLim->setText("15");
     ui->lineEdit_Span->setText("1.0");
     ui->comboBox_LeftColor->addItem("White");
     ui->comboBox_LeftColor->addItem("Yellow");
@@ -51,6 +52,7 @@ void MainWindow::on_pushButton_Convert_clicked()
     xparam.fDisLeft = ui->lineEdit_LeftDis->text().toDouble();
     xparam.fDisRight = ui->lineEdit_RIghtDis->text().toDouble();
     xparam.fSpan = ui->lineEdit_Span->text().toDouble();
+    xparam.fVelLim = ui->lineEdit_VelLim->text().toDouble()/3.6;
     if(ui->comboBox_LeftColor->currentText() == "White")
     {
         xparam.strColorLeft = "W";

+ 34 - 8
src/tool/tool_trace2vectormap/mainwindow.ui

@@ -182,7 +182,7 @@
     <property name="geometry">
      <rect>
       <x>30</x>
-      <y>330</y>
+      <y>308</y>
       <width>71</width>
       <height>41</height>
      </rect>
@@ -195,7 +195,7 @@
     <property name="geometry">
      <rect>
       <x>95</x>
-      <y>330</y>
+      <y>308</y>
       <width>121</width>
       <height>41</height>
      </rect>
@@ -205,7 +205,7 @@
     <property name="geometry">
      <rect>
       <x>369</x>
-      <y>330</y>
+      <y>308</y>
       <width>121</width>
       <height>41</height>
      </rect>
@@ -215,7 +215,7 @@
     <property name="geometry">
      <rect>
       <x>300</x>
-      <y>330</y>
+      <y>308</y>
       <width>61</width>
       <height>41</height>
      </rect>
@@ -228,7 +228,7 @@
     <property name="geometry">
      <rect>
       <x>631</x>
-      <y>330</y>
+      <y>308</y>
       <width>121</width>
       <height>41</height>
      </rect>
@@ -238,7 +238,7 @@
     <property name="geometry">
      <rect>
       <x>560</x>
-      <y>330</y>
+      <y>308</y>
       <width>61</width>
       <height>41</height>
      </rect>
@@ -250,8 +250,8 @@
    <widget class="QPushButton" name="pushButton_Convert">
     <property name="geometry">
      <rect>
-      <x>290</x>
-      <y>430</y>
+      <x>280</x>
+      <y>480</y>
       <width>151</width>
       <height>41</height>
      </rect>
@@ -260,6 +260,32 @@
      <string>Convert</string>
     </property>
    </widget>
+   <widget class="QLineEdit" name="lineEdit_VelLim">
+    <property name="geometry">
+     <rect>
+      <x>169</x>
+      <y>380</y>
+      <width>121</width>
+      <height>41</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string/>
+    </property>
+   </widget>
+   <widget class="QLabel" name="label_12">
+    <property name="geometry">
+     <rect>
+      <x>30</x>
+      <y>380</y>
+      <width>121</width>
+      <height>41</height>
+     </rect>
+    </property>
+    <property name="text">
+     <string>LimVel(km/h)</string>
+    </property>
+   </widget>
   </widget>
   <widget class="QMenuBar" name="menubar">
    <property name="geometry">

+ 2 - 2
src/tool/tool_trace2vectormap/trace2vectormap.cpp

@@ -267,13 +267,13 @@ int trace2vectormap::convert()
 
     for(i=0;i<(int)xvectorlane.size();i++)
     {
-        snprintf(strline,1000,"%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d\n",
+        snprintf(strline,1000,"%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%d,%f,%f,%d,%d\n",
                  xvectorlane[i].lnid,xvectorlane[i].did,xvectorlane[i].blid,
                  xvectorlane[i].flid,xvectorlane[i].bnid,xvectorlane[i].fnid,
                  0,0,0,0,
                  0,0,0,0,
                  1,xvectorlane[i].lcnt,xvectorlane[i].lno,0,
-                 20,20,0,0);
+                 xparam.fVelLim,xparam.fVelLim,0,0);
         xFileLane.write(strline);
     }
     xFileLane.close();

+ 1 - 0
src/tool/tool_trace2vectormap/trace2vectormap.h

@@ -17,6 +17,7 @@ struct trace2vectormap_param
     double fDisRight;
     std::string strColorLeft;
     std::string strColorRight;
+    double fVelLim;
 };
 
 namespace vectormap {