Pārlūkot izejas kodu

修改导航定位信息bug

madesheng 4 gadi atpakaļ
vecāks
revīzija
07b84ba1b2

+ 6 - 15
src/canbus/canbus.cpp

@@ -107,18 +107,11 @@ int Canbus::Start() {
                                                               &Canbus::StrActCtrRequest, this);
   ros::ServiceServer PedalActCtrService = node_handle_->advertiseService(robot::common::PedalActCtrService,
                                                               &Canbus::PedalActCtrRequest, this);
-
   ros::ServiceServer RBTManagerService = node_handle_->advertiseService(robot::common::RBTManagerService,
                                                               &Canbus::RBTManager, this);
   //data receive
   while(ros::ok())
   {
-//       canbus::canMsg rosMsg ;
-//       rosMsg.id = 10;
-//       rosMsg.data = "test";
-//       canRCUData_pub.publish(rosMsg);
-//       LOG(INFO)<<Name()<<" Publish CanData :" << "ID:" << rosMsg.id << ",Data:"<<rosMsg.data;
-
       read_loop();
       canObdData_pub.publish(obd);
       ros::spinOnce();
@@ -138,18 +131,19 @@ void Canbus::OnTimer(const ros::TimerEvent &) {
   }
   icuMonitor.uiICUAlive = heatbeat++;
   heatbeat ++;
-  TPCANMsg canStatus1; //VehicleStaus1 Can Message
-  TPCANMsg canIcuMonitor; //ICUMonitor Can Message
-  TPCANMsg canStatus2;  //VehicleStatus2 Can Message
-  TPCANMsg canStatus3;  //VehicleStatus3 Can Message
+
   try
   {
+      TPCANMsg canIcuMonitor; //ICUMonitor Can Message
       MessageCoder::CanMsgPackage((void*)&icuMonitor, robot::common::ICUMonitor, &canIcuMonitor);
       write_data(&canIcuMonitor);
+      TPCANMsg canStatus1; //VehicleStaus1 Can Message
       MessageCoder::CanMsgPackage((void*)&status1, robot::common::VehicleStatus1, &canStatus1);
-       write_data(&canStatus1);
+      write_data(&canStatus1);
+      TPCANMsg canStatus2;  //VehicleStatus2 Can Message
       MessageCoder::CanMsgPackage((void*)&status2, robot::common::VehicleStatus2, &canStatus2);
       write_data(&canStatus2);
+      TPCANMsg canStatus3;  //VehicleStatus3 Can Message
       MessageCoder::CanMsgPackage((void*)&status3, robot::common::VehicleStatus3, &canStatus3);
       write_data(&canStatus3);
       // enable
@@ -197,7 +191,6 @@ void Canbus::InitServiceAndMsg()
      request.uiStrMotEnReq = MOT_EN_REQ_ENABLE;
      request.uiXSftMotEnReq = MOT_EN_REQ_ENABLE;
      request.uiYSftMotEnReq = MOT_EN_REQ_ENABLE;
-
      MessageCoder::CanMsgPackage((void*)&request, robot::common::ActuatorEnableReq, &canActuaEnableReqMsg);
 
      T_RBT_MANAGER manager;
@@ -208,7 +201,6 @@ void Canbus::InitServiceAndMsg()
      manager.uiStrMotInt= FLT_CLR_RESET;
      manager.uiXSftMotInt = FLT_CLR_RESET;
      manager.uiYSftMotInt = FLT_CLR_RESET;
-
      MessageCoder::CanMsgPackage((void*)&manager, robot::common::RobotManager, &canRobotManagerMsg);
 }
 
@@ -293,7 +285,6 @@ int Canbus::read_data(TPCANMsg *pMsgBuff)
             pMsgBuff->ID ==robot::common::EstopInfo || pMsgBuff->ID ==robot::common::EstopErr)
     {
         publish_data(pMsgBuff);
-
     }
     return ROBOT_SUCCESS;
 }

+ 8 - 8
src/decision/decision.cpp

@@ -22,7 +22,7 @@ std::string Decision::Name() const { return "decision"; }
 
 int Decision::Init(){
 
-    LOG(INFO)<<Name()<<": init...";
+    LOG(INFO)<<Name()<<": init() start...";
     node_handle_.reset(new ros::NodeHandle());
     DecisionDatabase::InitDB();
     iCommandCmd = 0;// set undefied mode
@@ -31,13 +31,13 @@ int Decision::Init(){
     uiCarMode =6; // undefied
 
     PlanRouteName = "siasun";
-    LOG(INFO)<<Name()<<" init...";
+    LOG(INFO)<<Name()<<" init() end.";
     return ROBOT_SUCCESS;
 
 }
 
 int Decision::Start(){
-    LOG(INFO)<<Name()<<" start...";
+    LOG(INFO)<<Name()<<" start() start...";
     ros::ServiceServer CommandService = node_handle_->advertiseService(robot::common::CommandModeCmdService,
                                                                 &Decision::CommandRequestService, this);
     ros::Subscriber GeometrySub = node_handle_->subscribe(robot::common::Geometry, 2000,
@@ -55,14 +55,14 @@ int Decision::Start(){
 
     ros::AsyncSpinner spinner(6); // Use 6 threads
     spinner.start();
-    spinner.stop();
     ros::waitForShutdown();
-    LOG(INFO)<<Name()<<" end.";
+    LOG(INFO)<<Name()<<"  start() end.";
     return ROBOT_SUCCESS;
 }
 
 void Decision::Stop(){
-    LOG(INFO)<<Name()<<": stop...";
+    LOG(INFO)<<Name()<<": stop start...";
+      LOG(INFO)<<Name()<<": stop end.";
     return ;
 }
 
@@ -150,13 +150,13 @@ void Decision::RTKLocationCallback(const localization::localMsg::ConstPtr& msg)
 void Decision::OBDCallback(const canbus::obdMsg::ConstPtr& msg)
 {
     fCarNowSpeed = msg->VehSpd;
-    LOG(INFO)<<Name()<< "car real speed:"<<fCarNowSpeed;
+    LOG(INFO)<<Name()<< " car real speed:"<<fCarNowSpeed;
 }
 
 void Decision::RCUModeCallback(const perception::si2Msg::ConstPtr& msg)
 {
    uiCarMode = msg->CtrMdStat;
-   LOG(INFO)<<Name()<< "car excute mode :"<<uiCarMode;
+   LOG(INFO)<<Name()<< " car excute mode :"<<uiCarMode;
 }
 
 void Decision::ExcutePlanRoute(const localization::localMsg::ConstPtr& msg)

+ 27 - 6
src/decision/decision.h

@@ -77,32 +77,53 @@ public:
     void Stop() override;
 
 private:
+    /**
+    * RTK定位回调函数
+    */
     void RTKLocationCallback(const localization::localMsg::ConstPtr& msg);
 
+    /**
+    * OBD车辆信息回调函数
+    */
     void OBDCallback(const canbus::obdMsg::ConstPtr& msg);
 
+    /**
+    * RCU当前模式回调函数
+    */
     void RCUModeCallback(const perception::si2Msg::ConstPtr& msg);
 
+    /**
+    * ICU当前执行命令服务
+    */
     bool CommandRequestService(decision::CommandModeCmd::Request &req,
                         decision::CommandModeCmd::Response &res);
 
+    /**
+    * 执行保存规划路径
+    */
     void ExcutePlanRoute(const localization::localMsg::ConstPtr& msg);
 
+    /**
+    * 停止规划路径
+    */
     void StopPlanRoute(const localization::localMsg::ConstPtr& msg);
 
+    /**
+    * 执行自动驾驶任务
+    */
     void ExcuteSelfDriving(const localization::localMsg::ConstPtr& msg);
 
+    //速度控制
     unsigned int SpeedControl(double &speed);
-
+    //方向控制
     unsigned int StreeControl(double &streer);
-
+    //档位控制
     unsigned int BreakCtrControl(unsigned int breakmode);
-
+    //加载规划路径
     void LoadPlanRoute();
-
-
+    //车辆自动驾驶停止
     bool CarAutoDriveStop();
-
+    //更新测试用例结果
     bool UpdataCarRuleResults();
 
     void MPC_Controller(std::vector<double> &ptsx, std::vector<double> &ptsy,

+ 94 - 85
src/localization/localization.cpp

@@ -20,7 +20,6 @@ std::string Localization::Name() const { return "localization"; }
 int Localization::Init() {
     try
     {
-
         LOG(INFO)<<Name()<<" init start ...";
         serial_port = "/dev/ttyUSB0";
         baudrate = 115200;
@@ -40,22 +39,39 @@ int Localization::Start() {
  LOG(INFO)<<Name()<<" start start...";
  try
  {
+     geometry_pub = node_handle_->advertise<localization::localMsg>(robot::common::Geometry, 200);
      //设置串口属性,并打开串口
      serial_gnss.setPort(serial_port);
      serial_gnss.setBaudrate(baudrate);
      serial::Timeout to = serial::Timeout::simpleTimeout(timeout);
      serial_gnss.setTimeout(to);
      serial_gnss.open();
+     if (IsOpen())
+     {
+         //指定循环的频率
+         ros::Rate loop_rate(50);
+         while(ros::ok())
+         {
+
+           if(serial_gnss.available() >0){
+               LOG(INFO)<<Name()<<"  Reading from serial port. data size :"<<serial_gnss.available();
+               std::string strSerialResult;
+               strSerialResult= serial_gnss.read(serial_gnss.available());
+               LOG(INFO)<<Name()<<"  Read: " << strSerialResult;
+               NMEA0183 nmea;
+               if (Analyse(strSerialResult, nmea) == ROBOT_SUCCESS)
+                   PublishData(nmea);
+           }
+           ros::spinOnce();
+           loop_rate.sleep();
+         }
+     }
  }
  catch (serial::IOException& e)
  {
      LOG(ERROR)<<Name()<< " Unable to open port " << e.what();
      return ROBOT_FAILTURE;
  }
- if (IsOpen())
- {
-   GetSerialData();
- }
  LOG(INFO)<<Name()<<" start end.";
  return ROBOT_SUCCESS;
 }
@@ -75,36 +91,6 @@ bool Localization::IsOpen()
   }
 }
 
-int Localization::GetSerialData()
-{
-  try
-  {
-    //指定循环的频率
-    ros::Rate loop_rate(50);
-    while(ros::ok())
-    {
-
-      if(serial_gnss.available() >0){
-          LOG(INFO)<<Name()<<"Reading from serial port\n";
-          std::string strSerialResult;
-          strSerialResult= serial_gnss.read(serial_gnss.available());
-          LOG(INFO)<<Name()<<"Read: " << strSerialResult;
-          NMEA0183 nmea;
-          Analyse(strSerialResult, nmea);
-          PublishData(nmea);
-      }
-      //处理ROS的信息,比如订阅消息,并调用回调函数
-      ros::spinOnce();
-      loop_rate.sleep();
-    }
-  }
-  catch(ros::Exception ex)
-  {
-    LOG(ERROR)<<Name()<< " get serial data  error" << ex.what();
-    return ROBOT_FAILTURE;
-  }
-  return ROBOT_SUCCESS;
-}
 
 void Localization::Stop() {
   LOG(INFO)<<Name()<<" Stop start...";
@@ -115,7 +101,7 @@ void Localization::Stop() {
 
 int Localization::Analyse(const std::string &strSerialResult,  NMEA0183 &nmea){
 
-    LOG(INFO)<<Name()<<"Analyse start\n";
+    LOG(INFO)<<Name()<<" Analyse start.";
     try
     {
         std::string delim("$");
@@ -125,21 +111,26 @@ int Localization::Analyse(const std::string &strSerialResult,  NMEA0183 &nmea){
         std::vector<std::string>::iterator iter;
         for ( iter = iter_start; iter != iter_end; iter++)
         {
-            std::string type = (*iter).substr(0, 4);
+            std::string type = (*iter).substr(1, 5);
+            LOG(INFO)<<Name()<<" type:"<<type;
             if (type.compare("GPRMC") == 0)
             {
                 GPRMC temGPRMC;
-                ParaGPRMC(*iter, temGPRMC);
+                if (ParaGPRMC(*iter, temGPRMC) != ROBOT_SUCCESS)
+                     return ROBOT_FAILTURE;
                 nmea.gprmc = temGPRMC;
-                LOG(INFO)<<Name()<<"para GPRMC end\n";
+                nmea.gprmc.print();
+                LOG(INFO)<<Name()<<"para GPRMC end.";
             }
 
             else if (type.compare("GPGGA") == 0)
             {
                 GPGGA tempGPGGA;
-                ParaGPGGA(*iter, tempGPGGA);
+                if (ParaGPGGA(*iter, tempGPGGA) != ROBOT_SUCCESS)
+                     return ROBOT_FAILTURE;
                 nmea.gpgga = tempGPGGA;
-                LOG(INFO)<<Name()<<"para GPGGA end\n";
+                nmea.gpgga.print();
+                LOG(INFO)<<Name()<<" para GPGGA end.";
             }
         }
 
@@ -149,59 +140,79 @@ int Localization::Analyse(const std::string &strSerialResult,  NMEA0183 &nmea){
         LOG(ERROR)<<Name()<< " Analyse  error" << ex.what();
         return ROBOT_FAILTURE;
     }
-    LOG(INFO)<<Name()<<"Analyse end\n";
+    LOG(INFO)<<Name()<<" Analyse end.";
     return ROBOT_SUCCESS;
 
 }
 
 
-void Localization::ParaGPRMC(std::string &strGPRMC, GPRMC &gprmc){
-  std::vector<std::string> nmea_gprmc = Split(strGPRMC, ",");
-  gprmc.utcTime = atof(nmea_gprmc[1].c_str());
-  memset(&gprmc.locationStatus, 0x00, 2);
-  memcpy(&gprmc.locationStatus, nmea_gprmc[2].c_str(), 1);
-  gprmc. Latitude = StrToDouble(nmea_gprmc[3].c_str(), 2);
-  memset(&gprmc.LatType, 0x00, 2);
-  memcpy(&gprmc.LatType, nmea_gprmc[4].c_str(), 1);
-  gprmc.Longitude = StrToDouble(nmea_gprmc[5].c_str(), 3);
-  memset(&gprmc.LonType, 0x00, 2);
-  memcpy(&gprmc.LonType, nmea_gprmc[6].c_str(), 1);
-  gprmc.Speed = atof(nmea_gprmc[7].c_str());
-  gprmc.Deviated = atof(nmea_gprmc[8].c_str());
-  memset(&gprmc.Date, 0x00, 5);
-  memcpy(&gprmc.Date, nmea_gprmc[9].c_str(), 4);
-  gprmc.Magnetic = atof(nmea_gprmc[10].c_str());
-  memset(&gprmc.MagneticDirection, 0x00, 2);
-  memcpy(&gprmc.MagneticDirection, nmea_gprmc[11].c_str(), 1);
-  memset(&gprmc.Mode, 0x00, 2);
-  memcpy(&gprmc.Mode, nmea_gprmc[12].c_str(), 1);
+int Localization::ParaGPRMC(std::string &strGPRMC, GPRMC &gprmc){
+    try
+    {
+        std::vector<std::string> nmea_gprmc = Split(strGPRMC, ",");
+        gprmc.utcTime = atof(nmea_gprmc[1].c_str());
+        memset(&gprmc.locationStatus, 0x00, 2);
+        memcpy(&gprmc.locationStatus, nmea_gprmc[2].c_str(), 1);
+        gprmc. Latitude = StrToDouble(nmea_gprmc[3].c_str(), 2);
+        memset(&gprmc.LatType, 0x00, 2);
+        memcpy(&gprmc.LatType, nmea_gprmc[4].c_str(), 1);
+        gprmc.Longitude = StrToDouble(nmea_gprmc[5].c_str(), 3);
+        memset(&gprmc.LonType, 0x00, 2);
+        memcpy(&gprmc.LonType, nmea_gprmc[6].c_str(), 1);
+        gprmc.Speed = atof(nmea_gprmc[7].c_str());
+        gprmc.Deviated = atof(nmea_gprmc[8].c_str());
+        memset(&gprmc.Date, 0x00, 5);
+        memcpy(&gprmc.Date, nmea_gprmc[9].c_str(), 4);
+        gprmc.Magnetic = atof(nmea_gprmc[10].c_str());
+        memset(&gprmc.MagneticDirection, 0x00, 2);
+        memcpy(&gprmc.MagneticDirection, nmea_gprmc[11].c_str(), 1);
+        memset(&gprmc.Mode, 0x00, 2);
+        memcpy(&gprmc.Mode, nmea_gprmc[12].c_str(), 1);
+    }
+    catch (ros::Exception ex)
+    {
+        LOG(ERROR)<<Name()<< " ParaGPRMC  error" << ex.what();
+        return ROBOT_FAILTURE;
+    }
+     return ROBOT_SUCCESS;
 }
 
-void Localization::ParaGPGGA(std::string &strGPGGA, GPGGA &gpgga){
-    std::vector<std::string> nmea_gpgga = Split(strGPGGA, ",");
-    gpgga.utcTime = atof(nmea_gpgga[1].c_str());
-    gpgga. Latitude = StrToDouble(nmea_gpgga[2].c_str(), 2);
-    memset(&gpgga.LatType, 0x00, 2);
-    memcpy(&gpgga.LatType, nmea_gpgga[3].c_str(), 1);
-    gpgga.Longitude = StrToDouble(nmea_gpgga[4].c_str(), 3);
-    memset(&gpgga.LonType, 0x00, 2);
-    memcpy(&gpgga.LonType, nmea_gpgga[5].c_str(), 1);
-    memset(&gpgga.GPSStatus, 0x00, 5);
-    memcpy(&gpgga.GPSStatus, nmea_gpgga[6].c_str(), 4);
-    gpgga.SatelliteNumber = atoi(nmea_gpgga[7].c_str());
-    gpgga.Hdop = atof(nmea_gpgga[8].c_str());
-    gpgga.Height = atof(nmea_gpgga[9].c_str());
-    gpgga.ReleaveHeight = atoi(nmea_gpgga[10].c_str());
-    gpgga.CTKTime = atof(nmea_gpgga[11].c_str());
-    gpgga.CTKID = atoi(nmea_gpgga[12].c_str());
-    memset(&gpgga.Check, 0x00, 5);
-    memcpy(&gpgga.Check, nmea_gpgga[13].c_str(), 4);
+int Localization::ParaGPGGA(std::string &strGPGGA, GPGGA &gpgga){
+    try
+    {
+        std::vector<std::string> nmea_gpgga = Split(strGPGGA, ",");      
+        gpgga.utcTime = atof(nmea_gpgga[1].c_str());
+        if (nmea_gpgga[2].compare("") == 0)
+             return ROBOT_FAILTURE;
+        gpgga.Latitude = StrToDouble(nmea_gpgga[2].c_str(), 2);
+        memset(&gpgga.LatType, 0x00, 2);
+        memcpy(&gpgga.LatType, nmea_gpgga[3].c_str(), 1);
+        gpgga.Longitude = StrToDouble(nmea_gpgga[4].c_str(), 3);
+        memset(&gpgga.LonType, 0x00, 2);
+        memcpy(&gpgga.LonType, nmea_gpgga[5].c_str(), 1);
+        memset(&gpgga.GPSStatus, 0x00, 5);
+        memcpy(&gpgga.GPSStatus, nmea_gpgga[6].c_str(), 4);
+        gpgga.SatelliteNumber = atoi(nmea_gpgga[7].c_str());
+        gpgga.Hdop = atof(nmea_gpgga[8].c_str());
+        gpgga.Height = atof(nmea_gpgga[9].c_str());
+        gpgga.ReleaveHeight = atoi(nmea_gpgga[10].c_str());
+        gpgga.CTKTime = atof(nmea_gpgga[11].c_str());
+        gpgga.CTKID = atoi(nmea_gpgga[12].c_str());
+        memset(&gpgga.Check, 0x00, 5);
+        memcpy(&gpgga.Check, nmea_gpgga[13].c_str(), 4);
+    }
+    catch(ros::Exception ex)
+    {
+        LOG(ERROR)<<Name()<< " ParaGPGGA  error" << ex.what();
+        return ROBOT_FAILTURE;
+    }
+    return ROBOT_SUCCESS;
 }
 
 
 int Localization::PublishData(NMEA0183 &nmea)
 {
-    LOG(INFO)<<Name()<<"PublishData start\n";
+    LOG(INFO)<<Name()<<" PublishData start\n";
     try{
 
         double northing, easting;
@@ -212,8 +223,6 @@ int Localization::PublishData(NMEA0183 &nmea)
         localization.Latitude = nmea.gprmc.Latitude;
         localization.Height = nmea.gpgga.Height;
         localization.AngleDeviated = nmea.gprmc.Deviated;
-
-        ros::Publisher geometry_pub = node_handle_->advertise<localization::localMsg>(robot::common::Geometry, 200);
         geometry_pub.publish(localization);
     }
     catch (ros::Exception ex)
@@ -221,7 +230,7 @@ int Localization::PublishData(NMEA0183 &nmea)
         LOG(ERROR)<<Name()<< " PublishData  error" << ex.what();
         return ROBOT_FAILTURE;
     }
-    LOG(INFO)<<Name()<<"PublishData end\n";
+    LOG(INFO)<<Name()<<" PublishData end\n";
     return ROBOT_SUCCESS;
 
 }

+ 7 - 9
src/localization/localization.h

@@ -62,22 +62,16 @@ class Localization : public robot::common::RobotApp{
   void Stop() override;
 
  private:
-  // void PublishChassis();
-  // void PublishChassisDetail();
-  // void OnControlCommand(const apollo::control::ControlCommand &control_command);
-  // apollo::common::Status OnError(const std::string &error_msg);
-  // void RegisterCanClients();
-  bool IsOpen();
 
-  int GetSerialData();
+  bool IsOpen();
 
   int Analyse(const std::string &strSerialResult, NMEA0183 &nmea);
 
   std::vector<std::string> Split(const std::string& in, const std::string& delim);
 
-  void ParaGPRMC(std::string &nmea_gprmc, GPRMC &gprmc);
+  int ParaGPRMC(std::string &nmea_gprmc, GPRMC &gprmc);
 
-  void ParaGPGGA(std::string &nmea_gpgga, GPGGA &gpgga);
+  int ParaGPGGA(std::string &nmea_gpgga, GPGGA &gpgga);
   /**
    * @brief string localization ddmm convert to double dd type
    * @param strResult
@@ -110,7 +104,11 @@ private:
 
   serial::Serial serial_gnss; //声明串口对象
 
+  ros::Publisher geometry_pub;
+
 };
+
+
 }  // namespace localization
 }  // namespace robot
 

+ 36 - 1
src/localization/localizationdata.h

@@ -4,7 +4,7 @@
  * Licensed under the Apache License, Version 1.0 (the "License");
  *****************************************************************************/
 
-#include <math.h>
+
 /**
  * @file
  */
@@ -12,6 +12,10 @@
 #ifndef ROBOT_ROBOT_LOCALIZATIONDATA_H_
 #define ROBOT_ROBOT_LOCALIZATIONDATA_H_
 
+#include <math.h>
+#include <string>
+#include "../common/gloghelper.h"
+
 /**
  * @namespace robot::localization
  * @brief robot::localization
@@ -73,6 +77,21 @@ struct GPRMC
     char MagneticDirection[2];
     // <12> 模式指示(仅NMEA0183 3.00版本输出,A=自主定位,D=差分,E=估算,N=数据无效)
     char Mode[2];
+    void print()
+    {
+        LOG(INFO)<< "utcTime:"<<utcTime;
+        LOG(INFO)<< "locationStatus:"<<std::string(locationStatus);
+        LOG(INFO)<< "Latitude:"<<Latitude;
+        LOG(INFO)<< "LatType:"<<std::string(LatType);
+        LOG(INFO)<< "Longitude:"<<Longitude;
+        LOG(INFO)<< "LonType:"<<std::string(LonType);
+        LOG(INFO)<< "Speed:"<<Speed;
+        LOG(INFO)<< "Deviated:"<<Deviated;
+        LOG(INFO)<< "Date:"<<std::string(Date);
+        LOG(INFO)<< "Magnetic:"<<Magnetic;
+        LOG(INFO)<< "MagneticDirection:"<<std::string(MagneticDirection);
+        LOG(INFO)<< "Mode:"<<std::string(Mode);
+    }
 };
 
 /**
@@ -106,6 +125,22 @@ struct GPGGA
     int  CTKID;
     // 字段13:校验值
     char Check[5];
+    void print()
+    {
+        LOG(INFO)<< "utcTime:"<<utcTime;
+        LOG(INFO)<< "Latitude:"<<Latitude;
+        LOG(INFO)<< "LatType:"<<std::string(LatType);
+        LOG(INFO)<< "Longitude:"<<Longitude;
+        LOG(INFO)<< "LonType:"<<std::string(LonType);
+        LOG(INFO)<< "GPSStatus:"<<std::string(GPSStatus);
+        LOG(INFO)<< "SatelliteNumber:"<<SatelliteNumber;
+        LOG(INFO)<< "Hdop:"<<Hdop;
+        LOG(INFO)<< "Height:"<<Height;
+        LOG(INFO)<< "ReleaveHeight:"<<ReleaveHeight;
+        LOG(INFO)<< "CTKTime:"<<CTKTime;
+        LOG(INFO)<< "CTKID:"<<CTKID;
+        LOG(INFO)<< "Check:"<<std::string(Check);
+    }
 };
 
 /**