|
@@ -0,0 +1,408 @@
|
|
|
+/******************************************************************************
|
|
|
+ * Copyright 2017 The Apollo Authors. All Rights Reserved.
|
|
|
+ *
|
|
|
+ * Licensed under the Apache License, Version 2.0 (the "License");
|
|
|
+ * you may not use this file except in compliance with the License.
|
|
|
+ * You may obtain a copy of the License at
|
|
|
+ *
|
|
|
+ * http://www.apache.org/licenses/LICENSE-2.0
|
|
|
+ *
|
|
|
+ * Unless required by applicable law or agreed to in writing, software
|
|
|
+ * distributed under the License is distributed on an "AS IS" BASIS,
|
|
|
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
|
+ * See the License for the specific language governing permissions and
|
|
|
+ * limitations under the License.
|
|
|
+ *****************************************************************************/
|
|
|
+
|
|
|
+#include <filesystem>
|
|
|
+
|
|
|
+#include "gperftools/heap-profiler.h"
|
|
|
+#include "gperftools/malloc_extension.h"
|
|
|
+#include "gperftools/profiler.h"
|
|
|
+
|
|
|
+#include "cyber/common/global_data.h"
|
|
|
+#include "cyber/init.h"
|
|
|
+
|
|
|
+#include <iostream>
|
|
|
+#include "modules/dreamview_plus/backend/dreamview.h"
|
|
|
+
|
|
|
+#include <QSharedMemory>
|
|
|
+
|
|
|
+//#include "modules/dreamview_plus/modulecomm.h"
|
|
|
+
|
|
|
+#include "modules/dreamview_plus/proto/gpsimu.pb.h"
|
|
|
+#include "modules/dreamview_plus/proto/apolloctrlcmd.pb.h"
|
|
|
+#include "modules/dreamview_plus/proto/objectarray.pb.h"
|
|
|
+
|
|
|
+#include "modules/common_msgs/localization_msgs/localization.pb.h"
|
|
|
+#include "modules/common_msgs/control_msgs/control_cmd.pb.h"
|
|
|
+#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
|
|
|
+
|
|
|
+#include <QtCore/qglobal.h>
|
|
|
+#include <QDateTime>
|
|
|
+
|
|
|
+#include <functional>
|
|
|
+
|
|
|
+#include <GeographicLib/MGRS.hpp>
|
|
|
+#include <GeographicLib/UTMUPS.hpp>
|
|
|
+
|
|
|
+#include "modules/common/math/math_utils.h"
|
|
|
+#include "modules/common/math/quaternion.h"
|
|
|
+#include "modules/common/util/message_util.h"
|
|
|
+#include "modules/common/util/util.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,
|
|
|
+ ModuleComm_FASTRTPS_TCP = 3,
|
|
|
+ ModuleComm_UNDEFINE = 4
|
|
|
+};
|
|
|
+
|
|
|
+void * RegisterSend(const char * strcommname);
|
|
|
+
|
|
|
+
|
|
|
+void * RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount
|
|
|
+ ,ModuleComm_TYPE xmctype,const unsigned short nport);
|
|
|
+void * RegisterRecv(const char * strcommname,SMCallBack pCall,
|
|
|
+ ModuleComm_TYPE xmctype ,const char * strip,const unsigned short );
|
|
|
+void * RegisterRecvPlus(const char * strcommname,ModuleFun xFun,
|
|
|
+ ModuleComm_TYPE xmctype,const char * strip,const unsigned short );
|
|
|
+
|
|
|
+
|
|
|
+//void * MODULECOMMSHARED_EXPORT RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount
|
|
|
+// ,ModuleComm_TYPE xmctype = ModuleComm_UNDEFINE,const unsigned short nport = 5100);
|
|
|
+//void * MODULECOMMSHARED_EXPORT RegisterRecv(const char * strcommname,SMCallBack pCall,
|
|
|
+// ModuleComm_TYPE xmctype = ModuleComm_UNDEFINE,const char * strip = 0,const unsigned short = 5100);
|
|
|
+//void * MODULECOMMSHARED_EXPORT RegisterRecvPlus(const char * strcommname,ModuleFun xFun,
|
|
|
+// ModuleComm_TYPE xmctype = ModuleComm_UNDEFINE,const char * strip = 0,const unsigned short = 5100);
|
|
|
+
|
|
|
+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);
|
|
|
+
|
|
|
+void * RegisterSend(const char * strcommname,const unsigned int nBufSize,const unsigned int nMsgBufCount);
|
|
|
+void * RegisterRecv(const char * strcommname,SMCallBack pCall);
|
|
|
+void * RegisterRecvPlus(const char * strcommname,ModuleFun xFun);
|
|
|
+
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+std::shared_ptr<apollo::cyber::Writer<apollo::perception::PerceptionObstacles>> perception_writer_ = nullptr;
|
|
|
+
|
|
|
+std::shared_ptr<apollo::cyber::Writer<apollo::localization::LocalizationEstimate>>
|
|
|
+ localization_writer_;
|
|
|
+
|
|
|
+std::shared_ptr<apollo::cyber::Reader<apollo::control::ControlCommand>>
|
|
|
+ control_command_reader_;
|
|
|
+
|
|
|
+void * gpadecision;
|
|
|
+
|
|
|
+double gfutm_x = 0;
|
|
|
+double gfutm_y = 0;
|
|
|
+double gfutm_hdg = 0;
|
|
|
+
|
|
|
+using apollo::common::Point3D;
|
|
|
+using apollo::common::math::HeadingToQuaternion;
|
|
|
+using apollo::common::Quaternion;
|
|
|
+
|
|
|
+using apollo::common::math::InverseQuaternionRotate;
|
|
|
+using apollo::common::util::FillHeader;
|
|
|
+
|
|
|
+void TransformToVRF(const Point3D &point_mrf, const Quaternion &orientation,
|
|
|
+ Point3D *point_vrf) {
|
|
|
+ Eigen::Vector3d v_mrf(point_mrf.x(), point_mrf.y(), point_mrf.z());
|
|
|
+ auto v_vrf = InverseQuaternionRotate(orientation, v_mrf);
|
|
|
+ point_vrf->set_x(v_vrf.x());
|
|
|
+ point_vrf->set_y(v_vrf.y());
|
|
|
+ point_vrf->set_z(v_vrf.z());
|
|
|
+}
|
|
|
+
|
|
|
+void PublishLocalization(const double x,const double y,const double z,const double yaw,const double v,const double kappa,const double a) {
|
|
|
+ auto localization = std::make_shared<apollo::localization::LocalizationEstimate>();
|
|
|
+ FillHeader("SimPerfectControl", localization.get());
|
|
|
+ auto *pose = localization->mutable_pose();
|
|
|
+
|
|
|
+ pose->mutable_position()->set_x(x);
|
|
|
+ pose->mutable_position()->set_y(y);
|
|
|
+ pose->mutable_position()->set_z(z);
|
|
|
+ // Set orientation and heading
|
|
|
+ double cur_theta = yaw;
|
|
|
+
|
|
|
+
|
|
|
+
|
|
|
+ Eigen::Quaternion<double> cur_orientation =
|
|
|
+ HeadingToQuaternion<double>(cur_theta);
|
|
|
+ pose->mutable_orientation()->set_qw(cur_orientation.w());
|
|
|
+ pose->mutable_orientation()->set_qx(cur_orientation.x());
|
|
|
+ pose->mutable_orientation()->set_qy(cur_orientation.y());
|
|
|
+ pose->mutable_orientation()->set_qz(cur_orientation.z());
|
|
|
+ pose->set_heading(cur_theta);
|
|
|
+
|
|
|
+ // Set linear_velocity
|
|
|
+ pose->mutable_linear_velocity()->set_x(std::cos(cur_theta) * v);
|
|
|
+ pose->mutable_linear_velocity()->set_y(std::sin(cur_theta) * v);
|
|
|
+ pose->mutable_linear_velocity()->set_z(0);
|
|
|
+
|
|
|
+ // Set angular_velocity in both map reference frame and vehicle reference
|
|
|
+ // frame
|
|
|
+ pose->mutable_angular_velocity()->set_x(0);
|
|
|
+ pose->mutable_angular_velocity()->set_y(0);
|
|
|
+ pose->mutable_angular_velocity()->set_z(v*kappa);
|
|
|
+
|
|
|
+ TransformToVRF(pose->angular_velocity(), pose->orientation(),
|
|
|
+ pose->mutable_angular_velocity_vrf());
|
|
|
+
|
|
|
+ // Set linear_acceleration in both map reference frame and vehicle reference
|
|
|
+ // frame
|
|
|
+ auto *linear_acceleration = pose->mutable_linear_acceleration();
|
|
|
+ linear_acceleration->set_x(std::cos(cur_theta) * a);
|
|
|
+ linear_acceleration->set_y(std::sin(cur_theta) * a);
|
|
|
+ linear_acceleration->set_z(0);
|
|
|
+
|
|
|
+ TransformToVRF(pose->linear_acceleration(), pose->orientation(),
|
|
|
+ pose->mutable_linear_acceleration_vrf());
|
|
|
+ localization_writer_->Write(localization);
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+void onControl(
|
|
|
+ const std::shared_ptr<apollo::control::ControlCommand> &xCmd) {
|
|
|
+// std::lock_guard<std::mutex> lock(mutex_);
|
|
|
+
|
|
|
+// std::cout<<"steer: "<<xCmd->steering_target()<<" acc: "<<xCmd->acceleration()<<" brake:"<<xCmd->brake()<<std::endl;
|
|
|
+
|
|
|
+ iv::apollo::apolloctrlcmd xctrlcmd;
|
|
|
+ xctrlcmd.set_acceleration(xCmd->acceleration());
|
|
|
+ xctrlcmd.set_brake(xCmd->brake());
|
|
|
+ xctrlcmd.set_steering_target(xCmd->steering_target());
|
|
|
+
|
|
|
+ int nbytesize = (int)xctrlcmd.ByteSize();
|
|
|
+ std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[nbytesize]);
|
|
|
+ if(!xctrlcmd.SerializeToArray(pstr_ptr.get(),nbytesize))
|
|
|
+ {
|
|
|
+ std::cout<<" send ctrlcmd Serialize Fail. "<<std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+ iv::modulecomm::ModuleSendMsg(gpadecision,pstr_ptr.get(),nbytesize);
|
|
|
+}
|
|
|
+
|
|
|
+void ListenGPSIMU(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
|
|
|
+{
|
|
|
+ (void)index;
|
|
|
+ (void)dt;
|
|
|
+ (void)strmemname;
|
|
|
+ iv::gps::gpsimu xgpsimu;
|
|
|
+ if(!xgpsimu.ParseFromArray(strdata,nSize))
|
|
|
+ {
|
|
|
+ std::cout<<"ListenRaw Parse error."<<std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ // std::cout<<"recv gpsimu."<<std::endl;
|
|
|
+
|
|
|
+ double flon = xgpsimu.lon();
|
|
|
+ double flat = xgpsimu.lat();
|
|
|
+
|
|
|
+ double utm_x,utm_y;
|
|
|
+ int zone{};
|
|
|
+ bool is_north{};
|
|
|
+ GeographicLib::UTMUPS::Forward(flat, flon, zone, is_north, utm_x,utm_y);
|
|
|
+
|
|
|
+ PublishLocalization(utm_x,utm_y,xgpsimu.height(),(90-xgpsimu.heading())*M_PI/180.0,xgpsimu.speed(),0,0);
|
|
|
+}
|
|
|
+
|
|
|
+
|
|
|
+void ListenLiarTrack(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname){
|
|
|
+ iv::lidar::objectarray xobjarray;
|
|
|
+
|
|
|
+ if(!xobjarray.ParseFromArray(strdata,nSize))
|
|
|
+ {
|
|
|
+ std::cout<<" Parse Object Array Fail."<<std::endl;
|
|
|
+ return;
|
|
|
+ }
|
|
|
+
|
|
|
+ int nsize = static_cast<int>(xobjarray.obj_size());
|
|
|
+ int i;
|
|
|
+ auto perceptionobjs = std::make_shared<apollo::perception::PerceptionObstacles>();
|
|
|
+ FillHeader("SimPerfectControl", perceptionobjs.get());
|
|
|
+ for(i=0;i<nsize;i++){
|
|
|
+
|
|
|
+ iv::lidar::lidarobject * plidarobj = xobjarray.mutable_obj(i);
|
|
|
+ auto pobj = perceptionobjs->add_perception_obstacle();
|
|
|
+
|
|
|
+ double xbase = gfutm_x;
|
|
|
+ double ybase = gfutm_y;
|
|
|
+ pobj->set_id(i);
|
|
|
+ apollo::common::Point3D * ppos = new apollo::common::Point3D();
|
|
|
+ double xrot = 0;
|
|
|
+ double yrot = 0;
|
|
|
+ // std::cout<<" obj x: "<<plidarobj->position().x()<<" y:"<<plidarobj->position().y()<<std::endl;
|
|
|
+ xrot = plidarobj->position().y() * cos(gfutm_hdg) - plidarobj->position().x() * (-1.0) * sin(gfutm_hdg);
|
|
|
+ yrot = plidarobj->position().y() * sin(gfutm_hdg) + plidarobj->position().x() * (-1.0) * cos(gfutm_hdg);
|
|
|
+ ppos->set_x(xrot + xbase);
|
|
|
+ ppos->set_y(yrot + ybase);
|
|
|
+ ppos->set_z(plidarobj->position().z());
|
|
|
+ pobj->set_allocated_position(ppos);
|
|
|
+
|
|
|
+ double fobjhdg = plidarobj->tyaw() + gfutm_hdg;
|
|
|
+
|
|
|
+ double xp[4],yp[4];
|
|
|
+ double fpedlen = plidarobj->dimensions().x();
|
|
|
+ double fpedwidth = plidarobj->dimensions().y();
|
|
|
+ double fhdg = fobjhdg - M_PI/2.0;
|
|
|
+ double x = xrot;
|
|
|
+ double y = yrot;
|
|
|
+ xp[0] = x + (0 - fpedlen/2.0) * cos(fhdg) - (0 - fpedwidth/2.0) * sin(fhdg);
|
|
|
+ yp[0] = y + (0 - fpedlen/2.0) * sin(fhdg) + (0 - fpedwidth/2.0) * cos(fhdg);
|
|
|
+ xp[1] = x + (0 + fpedlen/2.0) * cos(fhdg) - (0 - fpedwidth/2.0) * sin(fhdg);
|
|
|
+ yp[1] = y + (0 + fpedlen/2.0) * sin(fhdg) + (0 - fpedwidth/2.0) * cos(fhdg);
|
|
|
+ xp[2] = x + (0 + fpedlen/2.0) * cos(fhdg) - (0 + fpedwidth/2.0) * sin(fhdg);
|
|
|
+ yp[2] = y + (0 + fpedlen/2.0) * sin(fhdg) + (0 + fpedwidth/2.0) * cos(fhdg);
|
|
|
+ xp[3] = x + (0 - fpedlen/2.0) * cos(fhdg) - (0 + fpedwidth/2.0) * sin(fhdg);
|
|
|
+ yp[3] = y + (0 - fpedlen/2.0) * sin(fhdg) + (0 + fpedwidth/2.0) * cos(fhdg);
|
|
|
+ apollo::common::Point3D * p1 = pobj->add_polygon_point();
|
|
|
+ p1->set_x(xp[1]+ xbase);p1->set_y(yp[1]+ ybase);p1->set_z(0);
|
|
|
+ apollo::common::Point3D * p2 = pobj->add_polygon_point();
|
|
|
+ p2->set_x(xp[2]+ xbase);p2->set_y(yp[2]+ ybase);p2->set_z(0);
|
|
|
+ apollo::common::Point3D * p3 = pobj->add_polygon_point();
|
|
|
+ p3->set_x(xp[3]+ xbase);p3->set_y(yp[3]+ ybase);p3->set_z(0);
|
|
|
+ apollo::common::Point3D * p4 = pobj->add_polygon_point();
|
|
|
+ p4->set_x(xp[0]+ xbase);p4->set_y(yp[0]+ ybase);p4->set_z(0);
|
|
|
+
|
|
|
+ pobj->set_length(fpedlen);
|
|
|
+ pobj->set_width(fpedwidth);
|
|
|
+ pobj->set_height(plidarobj->dimensions().z());
|
|
|
+
|
|
|
+ pobj->set_tracking_time(1.0);
|
|
|
+
|
|
|
+ apollo::common::Point3D * pvel = new apollo::common::Point3D();
|
|
|
+ pvel->set_x(0); pvel->set_y(0); pvel->set_z(0);
|
|
|
+ pobj->set_allocated_velocity(pvel);
|
|
|
+
|
|
|
+ apollo::common::Point3D * paccel = new apollo::common::Point3D();
|
|
|
+ paccel->set_x(0); paccel->set_y(0); paccel->set_z(0);
|
|
|
+ pobj->set_allocated_acceleration(paccel);
|
|
|
+
|
|
|
+ pobj->set_type(apollo::perception::PerceptionObstacle_Type_VEHICLE);
|
|
|
+
|
|
|
+
|
|
|
+ }
|
|
|
+
|
|
|
+ perception_writer_->Write(perceptionobjs);
|
|
|
+
|
|
|
+}
|
|
|
+
|
|
|
+int main(int argc, char* argv[]) {
|
|
|
+
|
|
|
+ std::cout<<" hello , adc dreamviewplus. 1226 16:03"<<std::endl;
|
|
|
+ double utm_x,utm_y;
|
|
|
+ int zone{};
|
|
|
+ bool is_north{};
|
|
|
+ GeographicLib::UTMUPS::Forward(39, 117, zone, is_north, utm_x,utm_y);
|
|
|
+ std::cout<<"utm x: "<<utm_x<<" utm y: "<<utm_y<<std::endl;
|
|
|
+ void * pa = iv::modulecomm::RegisterSend("hello",1000,1);
|
|
|
+ // set working directory to APOLLO_RUNTIME_PATH for relative file paths
|
|
|
+ const char* apollo_runtime_path = std::getenv("APOLLO_RUNTIME_PATH");
|
|
|
+ if (apollo_runtime_path != nullptr) {
|
|
|
+ if (std::filesystem::is_directory(
|
|
|
+ std::filesystem::status(apollo_runtime_path))) {
|
|
|
+ std::filesystem::current_path(apollo_runtime_path);
|
|
|
+ }
|
|
|
+ }
|
|
|
+ google::ParseCommandLineFlags(&argc, &argv, true);
|
|
|
+ // Added by caros to improve dv performance
|
|
|
+
|
|
|
+ std::signal(SIGTERM, [](int sig) {
|
|
|
+ apollo::cyber::OnShutdown(sig);
|
|
|
+ if (FLAGS_dv_cpu_profile) {
|
|
|
+ ProfilerStop();
|
|
|
+ }
|
|
|
+ if (FLAGS_dv_heap_profile) {
|
|
|
+ HeapProfilerDump("Befor shutdown");
|
|
|
+ HeapProfilerStop();
|
|
|
+ }
|
|
|
+ });
|
|
|
+
|
|
|
+ std::signal(SIGINT, [](int sig) {
|
|
|
+ apollo::cyber::OnShutdown(sig);
|
|
|
+ if (FLAGS_dv_cpu_profile) {
|
|
|
+ ProfilerStop();
|
|
|
+ }
|
|
|
+ if (FLAGS_dv_heap_profile) {
|
|
|
+ HeapProfilerDump("Befor shutdown");
|
|
|
+ HeapProfilerStop();
|
|
|
+ }
|
|
|
+ });
|
|
|
+
|
|
|
+ if (FLAGS_dv_cpu_profile) {
|
|
|
+ auto base_name_cpu = std::string(argv[0]) + "_cpu" + std::string(".prof");
|
|
|
+ ProfilerStart(base_name_cpu.c_str());
|
|
|
+ }
|
|
|
+ if (FLAGS_dv_heap_profile) {
|
|
|
+ auto base_name_heap = std::string(argv[0]) + "_heap" + std::string(".prof");
|
|
|
+ HeapProfilerStart(base_name_heap.c_str());
|
|
|
+ }
|
|
|
+
|
|
|
+ apollo::cyber::GlobalData::Instance()->SetProcessGroup("dreamview_sched");
|
|
|
+ apollo::cyber::Init(argv[0]);
|
|
|
+
|
|
|
+ auto talker_node = apollo::cyber::CreateNode("pilot_apollo_bridge");
|
|
|
+
|
|
|
+ localization_writer_ = talker_node->CreateWriter<apollo::localization::LocalizationEstimate>("/apollo/localization/adcpose");
|
|
|
+
|
|
|
+ perception_writer_ = talker_node->CreateWriter<apollo::perception::PerceptionObstacles>("/apollo/perception/obstacles");
|
|
|
+
|
|
|
+ control_command_reader_ = talker_node->CreateReader<apollo::control::ControlCommand>(
|
|
|
+ "/apollo/control",onControl);
|
|
|
+
|
|
|
+ void * paraw = iv::modulecomm::RegisterRecv("hcp2_gpsimu",ListenGPSIMU);
|
|
|
+ (void)paraw;
|
|
|
+
|
|
|
+ void * patrack = iv::modulecomm::RegisterRecv("lidar_track",ListenLiarTrack);
|
|
|
+ (void)patrack;
|
|
|
+
|
|
|
+ void * pactrl = iv::modulecomm::RegisterSend("apolloctrlcmd",10000,1);
|
|
|
+ gpadecision = pactrl;
|
|
|
+
|
|
|
+ apollo::dreamview::Dreamview dreamview;
|
|
|
+ const bool init_success = dreamview.Init().ok() && dreamview.Start().ok();
|
|
|
+ if (!init_success) {
|
|
|
+ AERROR << "Failed to initialize dreamview server";
|
|
|
+ return -1;
|
|
|
+ }
|
|
|
+ apollo::cyber::WaitForShutdown();
|
|
|
+ return 0;
|
|
|
+}
|