|
@@ -35,6 +35,8 @@ static void * g_lidar_pc_nofloor;
|
|
static void * glidar_pc_p;
|
|
static void * glidar_pc_p;
|
|
static void * glidar_per;
|
|
static void * glidar_per;
|
|
|
|
|
|
|
|
+static void * gpafusion;
|
|
|
|
+
|
|
iv::Ivfault *gfault = nullptr;
|
|
iv::Ivfault *gfault = nullptr;
|
|
iv::Ivlog *givlog = nullptr;
|
|
iv::Ivlog *givlog = nullptr;
|
|
|
|
|
|
@@ -101,7 +103,9 @@ static void writepctosm(pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud,void
|
|
int * pHeadSize = (int *)strOut;
|
|
int * pHeadSize = (int *)strOut;
|
|
*pHeadSize = 4 + point_cloud->header.frame_id.size()+4+8;
|
|
*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());
|
|
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()));
|
|
|
|
|
|
+// pcl::uint32_t * pu32 = (pcl::uint32_t *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
|
|
|
|
+
|
|
|
|
+ unsigned int * pu32 = (unsigned int *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
|
|
*pu32 = point_cloud->header.seq;
|
|
*pu32 = point_cloud->header.seq;
|
|
memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
|
|
memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
|
|
pcl::PointXYZI * p;
|
|
pcl::PointXYZI * p;
|
|
@@ -400,6 +404,54 @@ static void GridGetObs(pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud,std::s
|
|
|
|
|
|
#include <QTime>
|
|
#include <QTime>
|
|
|
|
|
|
|
|
+#include "fusionobjectarray.pb.h"
|
|
|
|
+
|
|
|
|
+void ShareFusionObject(void * pa ,std::shared_ptr<std::vector<iv::ObstacleBasic>> & lidar_obs)
|
|
|
|
+{
|
|
|
|
+ iv::fusion::fusionobjectarray xfusion;
|
|
|
|
+ double timestamp = std::chrono::system_clock::now().time_since_epoch().count();
|
|
|
|
+ timestamp = timestamp/1000000.0;
|
|
|
|
+
|
|
|
|
+ xfusion.set_timestamp(timestamp);
|
|
|
|
+
|
|
|
|
+ iv::fusion::fusionobject * pobj = xfusion.add_obj();
|
|
|
|
+
|
|
|
|
+ pobj->set_id(0);
|
|
|
|
+ pobj->set_type(0);
|
|
|
|
+ iv::fusion::VelXY xvel;
|
|
|
|
+ xvel.set_x(0);
|
|
|
|
+ xvel.set_y(0);
|
|
|
|
+ pobj->set_allocated_vel_abs(&xvel);
|
|
|
|
+ iv::fusion::Dimension xdim;
|
|
|
|
+ xdim.set_x(0.2);
|
|
|
|
+ xdim.set_y(0.2);
|
|
|
|
+ xdim.set_z(2.0);
|
|
|
|
+ pobj->set_allocated_dimensions(&xdim);
|
|
|
|
+
|
|
|
|
+ int i;
|
|
|
|
+ int nsize = lidar_obs->size();
|
|
|
|
+ for(i=0;i<nsize;i++)
|
|
|
|
+ {
|
|
|
|
+ iv::fusion::NomalXYZ * pcen = pobj->add_nomal_centroid();
|
|
|
|
+ pcen->set_nomal_x(lidar_obs->at(i).nomal_x);
|
|
|
|
+ pcen->set_nomal_y(lidar_obs->at(i).nomal_y);
|
|
|
|
+ pcen->set_nomal_z(lidar_obs->at(i).nomal_z);
|
|
|
|
+ }
|
|
|
|
+
|
|
|
|
+ int nbytesize = xfusion.ByteSize();
|
|
|
|
+ std::shared_ptr<char> pstr_ptr = std::shared_ptr<char>(new char[nbytesize]);
|
|
|
|
+
|
|
|
|
+ if(xfusion.SerializeToArray(pstr_ptr.get(),nbytesize))
|
|
|
|
+ {
|
|
|
|
+ iv::modulecomm::ModuleSendMsg(pa,pstr_ptr.get(),nbytesize);
|
|
|
|
+ }
|
|
|
|
+ else
|
|
|
|
+ {
|
|
|
|
+ std::cout<<" serialzie fusion fail."<<std::endl;
|
|
|
|
+ }
|
|
|
|
+
|
|
|
|
+
|
|
|
|
+}
|
|
|
|
|
|
|
|
|
|
static void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
|
|
static void ListenPointCloud(const char * strdata,const unsigned int nSize,const unsigned int index,const QDateTime * dt,const char * strmemname)
|
|
@@ -446,6 +498,8 @@ static void ListenPointCloud(const char * strdata,const unsigned int nSize,const
|
|
|
|
|
|
// std::cout<<"prc."<<std::endl;
|
|
// std::cout<<"prc."<<std::endl;
|
|
|
|
|
|
|
|
+ ShareFusionObject(gpafusion,lidar_obs);
|
|
|
|
+
|
|
if(g_robosys == 0)
|
|
if(g_robosys == 0)
|
|
{
|
|
{
|
|
if(lidar_obs->size() == 0)
|
|
if(lidar_obs->size() == 0)
|
|
@@ -484,6 +538,8 @@ void PERCEPTION_LIDAR_VV7SHARED_EXPORT StartPerception_lidar_vv7()
|
|
|
|
|
|
glidar_obs = iv::modulecomm::RegisterSend(gstr_outputmemname,20000000,3);
|
|
glidar_obs = iv::modulecomm::RegisterSend(gstr_outputmemname,20000000,3);
|
|
|
|
|
|
|
|
+ gpafusion = iv::modulecomm::RegisterSend("li_ra_fusion",10000000,1);
|
|
|
|
+
|
|
#ifdef OUT_GROUND
|
|
#ifdef OUT_GROUND
|
|
g_lidar_pc_floor = iv::modulecomm::RegisterSend("lidar_pc_floor",20000000,3);
|
|
g_lidar_pc_floor = iv::modulecomm::RegisterSend("lidar_pc_floor",20000000,3);
|
|
g_lidar_pc_nofloor = iv::modulecomm::RegisterSend("lidar_pc_nofloor",20000000,3);
|
|
g_lidar_pc_nofloor = iv::modulecomm::RegisterSend("lidar_pc_nofloor",20000000,3);
|