Ver Fonte

test src/ros to LGSVL.

yuchuli há 3 anos atrás
pai
commit
7284887ed6

+ 4 - 0
src/decition/decition_brain/decition_brain.pro

@@ -18,7 +18,9 @@ DEFINES += QT_DEPRECATED_WARNINGS
 
 SOURCES += $$PWD/../common/main.cpp \
     ../../include/msgtype/brainstate.pb.cc \
+    ../../include/msgtype/carstate.pb.cc \
     ../../include/msgtype/decition.pb.cc \
+    ../../include/msgtype/groupmsg.pb.cc \
     ../../include/msgtype/radarobjectarray.pb.cc \
     ../../include/msgtype/radarobject.pb.cc \
     ../../include/msgtype/gpsimu.pb.cc \
@@ -62,7 +64,9 @@ unix:!macx: DEPENDPATH += $$PWD/.
 
 HEADERS += \
     ../../include/msgtype/brainstate.pb.h \
+    ../../include/msgtype/carstate.pb.h \
     ../../include/msgtype/decition.pb.h \
+    ../../include/msgtype/groupmsg.pb.h \
     ../../include/msgtype/radarobjectarray.pb.h \
     ../../include/msgtype/radarobject.pb.h \
     ../../include/msgtype/gpsimu.pb.h \

+ 2 - 2
src/driver/driver_map_xodrload/globalplan.cpp

@@ -1191,7 +1191,7 @@ static std::vector<PlanPoint> getparampoly3dpoint(GeometryParamPoly3 * parc,cons
     pp.y = yold;
     pp.hdg = hdg0;
     pp.dis = 0;
-    xvectorPP.push_back(pp);
+//    xvectorPP.push_back(pp);
 
     double dt = 1.0;
     double tcount = parc->GetLength()/0.1;
@@ -1201,7 +1201,7 @@ static std::vector<PlanPoint> getparampoly3dpoint(GeometryParamPoly3 * parc,cons
     }
     double t;
     s = dt;
-    s = 0.1;
+    s = 0;
 
     double ua,ub,uc,ud,va,vb,vc,vd;
     ua = parc->GetuA();ub= parc->GetuB();uc= parc->GetuC();ud = parc->GetuD();

+ 11 - 0
src/driver/driver_odomtogpsimu/main.cpp

@@ -105,6 +105,17 @@ void ListenODOM(const char * strdata,const unsigned int nSize,const unsigned int
     double hdg_o = (90 - ghead0)*M_PI/180.0;
     double rel_x = xodom.pose_position().x() * cos(hdg_o) - xodom.pose_position().y() * sin(hdg_o);
     double rel_y = xodom.pose_position().x() * sin(hdg_o) + xodom.pose_position().y() * cos(hdg_o);
+
+    double fix_hdg = 90;//104.824;
+    double fix_x = -13.0;
+    double fix_y = 4.0;
+    double hdg_fix = (90 - fix_hdg)*M_PI/180.0;
+    double rel_fix_x = fix_x * cos(hdg_fix) - fix_y * sin(hdg_fix);
+    double rel_fix_y = fix_x * sin(hdg_fix) + fix_y * cos(hdg_fix);
+
+    rel_x = rel_x + rel_fix_x;
+    rel_y = rel_y + rel_fix_y;
+
     GaussProjInvCal(x_o + rel_x,y_o + rel_y,&lon,&lat);
     double hdg_c = hdg_o + xAng.yaw;
 

+ 1 - 1
src/ros/catkin/src/rostopilot/CMakeLists.txt

@@ -123,6 +123,6 @@ include_directories(
 
 
 ## Declare a C++ executable
-add_executable(${PROJECT_NAME}_node src/main.cpp ./../../../../include/msgtype/rawpic.pb.cc   ./../../../../include/msgtype/odom.pb.cc  )
+add_executable(${PROJECT_NAME}_node src/main.cpp ./../../../../include/msgtype/rawpic.pb.cc   ./../../../../include/msgtype/odom.pb.cc  ./../../../../include/msgtype/decition.pb.cc )
 target_link_libraries(${PROJECT_NAME}_node ${catkin_LIBRARIES}  ${OpenCV_LIBRARIES}    ${Protobuf_LIBRARIES}  Qt5Core Qt5Xml modulecomm)
 

+ 52 - 2
src/ros/catkin/src/rostopilot/src/main.cpp

@@ -22,6 +22,7 @@
 
 #include "rawpic.pb.h"
 #include "odom.pb.h"
+#include "decition.pb.h"
 
 static std::string _point_topic = "/points_raw";
 static std::string _point_msgname = "lidarpc_ros";
@@ -197,6 +198,54 @@ void testvh()
      }
 }
 
+void UpdateDecition(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
+{
+
+    static int x = 0;
+    iv::brain::decition xdecition;
+    std::cout<<" nSize : "<<nSize<<std::endl;
+    if(!xdecition.ParseFromArray(strdata,nSize))
+    {
+        std::cout<<" UpdateDecition Parse error."<<std::endl;
+        return;
+    }
+    //ServiceCarStatus.mfAcc = xdecition.accelerator();   //
+         autoware_msgs::VehicleCmd xcmd;
+
+         xcmd.header.seq = x;
+
+
+        std::cout<<" acc : "<<xdecition.accelerator()<<std::endl;
+        //xcmd.ctrl_cmd.linear_acceleration =0.1;
+          xcmd.twist_cmd.twist.linear.x =   xdecition.speed()/3.6;
+          xcmd.twist_cmd.twist.angular.z = 3.0* xdecition.wheelangle() /600.0; 
+         xcmd.ctrl_cmd.linear_velocity = 30.0;
+         //xcmd.ctrl_cmd.steering_angle = xdecition.wheelangle() * (-1.0)/600.0; 
+        //xcmd.gear_cmd.gear =  1;//autoware_msgs::VehicleCmd::_gear_cmd_type::NONE;
+        xcmd.mode = 1;
+        if(xdecition.leftlamp()  == true)
+        {
+            xcmd.lamp_cmd.l = 1;
+        }
+        else
+        {
+            xcmd.lamp_cmd.l = 0;
+        }
+        if(xdecition.rightlamp() == true)
+        {
+            xcmd.lamp_cmd.r = 1;
+        }
+        else
+        {
+            xcmd.lamp_cmd.r = 0;
+        }
+        // xcmd.lamp_cmd.l =  0;
+         //xcmd.lamp_cmd.r = 0;
+
+
+         test_cmd_pub.publish(xcmd);
+}
+
 int main(int argc, char *argv[])
 {
 	ros::init(argc, argv, "rostopilot");
@@ -226,14 +275,15 @@ int main(int argc, char *argv[])
     gpa_image = iv::modulecomm::RegisterSend(_image_msgname.data(),20000000,1);
     gpa_odom = iv::modulecomm::RegisterSend(_odom_msgname.data(),10000,1);
 
-   points_sub = private_nh.subscribe(_point_topic, 1, points_callback);
+  points_sub = private_nh.subscribe(_point_topic, 1, points_callback);
 
       image_transport::ImageTransport it(private_nh);
     image_transport::Subscriber sub = it.subscribe( _image_topic, 1, imageCalllback );
 
     odom_sub = private_nh.subscribe(_odom_topic,1,odomCalllback);
 
-    std::thread * pnew = new std::thread(testvh);
+    void * pdecition = iv::modulecomm::RegisterRecv("deciton",UpdateDecition);
+ //   std::thread * pnew = new std::thread(testvh);
 
    ros::spin();
    /*

+ 2 - 0
src/ui/ui_ads_hmi/ADCIntelligentVehicle.cpp

@@ -629,6 +629,8 @@ void ADCIntelligentVehicle::timeoutslot()
 
     if((mTimeState.elapsed()-mnTimeUpdateGPS) > 1000)
     {
+        oldrtkstatus = -1;
+        oldinstatus = -1;
         ui->pushButton_10->setStyleSheet("background-color: red");
         ui->pushButton_11->setStyleSheet("background-color: red");
         ui->pushButton_23->setStyleSheet("background-color: red");