提示:文章寫完後,目錄可以自動生成,如何生成可參考右邊的幫助文檔
文章目錄
- 前言
- 一、自動駕駛開源代碼
- 二、GNSS子產品
-
- 1.GNSS 資料結構
- 2.GNSS的訂閱子產品
- 三、點雲子產品
-
- 1.CloudData資料結構
- 總結
前言
提示:跟随大神手敲一遍自動駕駛代碼。
一、自動駕駛開源代碼
來源:
https://zhuanlan.zhihu.com/p/105512661
記錄出現的問題和進度
二、GNSS子產品
1.GNSS 資料結構
頭檔案:
- 類中為什麼設定static 成員函數、成員變量的?static成員變量為啥類外初始化?
- GeographicLib::localCartesia的作用是什麼?感覺像是gnss坐标轉換器
- deque的底層實作是什麼?常見用法?
- namespace的原理和使用方法?
- GNSS的資料結構
1.類中為什麼設定static 成員函數、成員變量的?static成員變量為啥類外初始化?
為啥設定static成員變量:這個變量存儲在靜态存儲區,每個類有隻有一個副本 和對象無關 所有對象共用這個副本,因為是類對象 通路範圍為該類。一般在外部類使用該static變量的時候就是用calssName::(static)varName來通路
為什麼設定成員函數:與類執行個體無關。把類名當成namespace用。控制該函數的通路權限。控制類内的static變量。
static成員變量為啥類外初始化: static 非const成員變量在類中隻是聲明,必須在類外定義.靜态資料成員實際上是類域中的全局變量。是以,靜态資料成員的定義(初始化)不應該被放在頭檔案中,應放到對應的cpp檔案。
其定義方式與全局變量相同,不要在頭檔案中定義(初始化)靜态資料成員.
2.GeographicLib::localCartesia的作用是什麼?
GeographicLib
.GeographicLib::localCartesia
将地理坐标系準變成xyz坐标系。
設定坐标原點,用地理坐标系初始化。
void GeographicLib::LocalCartesian::Reset ( real lat0,
real lon0,
real h0 = 0
)
将地理坐标系轉換成xyz坐标系
void GeographicLib::LocalCartesian::Forward ( real lat,
real lon,
real h,
real & x,
real & y,
real & z
) const
3.deque的底層實作是什麼?常見用法?
deque
4.namespace的原理和使用方法?
namespace
5.GNSS的資料結構
#include <deque>
#include "GeographicLib/src/LocalCartesian.hpp"
namespace lidar_localization {
class GNSSData {
private:
double time = 0.0;
double longitude = 0.0;//經度
double latitude = 0.0;//緯度
double altitude = 0.0;//海拔
double local_E = 0.0;
double local_N = 0.0;
double local_U = 0.0;
int status = 0;
int service = 0;
private:
static GeographicLib::localCartesian geo_converter;
static bool origin_position_inited;
public:
void InitOriginPosition();
void updataXYZ();
static bool SyncData(std::deque<GNSSData> unsyncedData, std::deque<GNSSData> syncedData, double sync_time);
};
}
源檔案:
-
glog的作用?glog的作用
glog的使用方法
- 資料同步處理的方法可以複用。
- 采用線性插值來進行時間同步
#include "lidar_localization/sensor_data/gnss_data.hpp"
#include "glog/logging.h"
bool lidar_localization::sensor_data::origin_position_inited = false;
GeographicLib::LocalCartesian lidar_localization::sensor_data:: geo_converter;
namespace lidar_loacalization{
void GNSSData::InitOriginPosition() {
geo_converter.Reset(latitude, longtitude, altitude);
origin_position_inited = true;
}
void GNSSData::updataXYZ(){
if (!origin_position_inited){
LOG(WARNING) << "GeoConverter has not not set origin position!";
}
geo_converter.Forward(latitude, longitude, altitude, local_E, local_N, local_U);
}
bool GNSSData::SyncData(std::deque<GNSSData>& UnsyncedData, std::deque<GNSSData>& SyncedData, double sync_time) {
// 傳感器資料按時間序列排列,在傳感器資料中為同步的時間點找到合适的時間位置
// 即找到與同步時間相鄰的左右兩個資料
// 需要注意的是,如果左右相鄰資料有一個離同步時間內插補點比較大,則說明資料有丢失,時間離得太遠不适合做內插補點
while (UnsyncedData.size() >= 2) {
if (UnsyncedData.front().time > sync_time)
return false;
if (UnsyncedData.at(1).time < sync_time) {
UnsyncedData.pop_front();
continue;
}
if (sync_time - UnsyncedData.front().time > 0.2) {
UnsyncedData.pop_front();
return false;
}
if (UnsyncedData.at(1).time - sync_time > 0.2) {
return false;
}
break;
}
if (UnsyncedData.size() < 2)
return false;
GNSSData front_data = UnsyncedData.at(0);
GNSSData back_data = UnsyncedData.at(1);
GNSSData synced_data;
double front_scale = (back_data.time - sync_time) / (back_data.time - front_data.time);
double back_scale = (sync_time - front_data.time) / (back_data.time - front_data.time);
synced_data.time = sync_time;
synced_data.status = back_data.status;
synced_data.longitude = front_data.longitude * front_scale + back_data.longitude * back_scale;
synced_data.latitude = front_data.latitude * front_scale + back_data.latitude * back_scale;
synced_data.altitude = front_data.altitude * front_scale + back_data.altitude * back_scale;
synced_data.local_E = front_data.local_E * front_scale + back_data.local_E * back_scale;
synced_data.local_N = front_data.local_N * front_scale + back_data.local_N * back_scale;
synced_data.local_U = front_data.local_U * front_scale + back_data.local_U * back_scale;
SyncedData.push_back(synced_data);
}
}
其中比較重要的是傳感器資料的時間同步:
1.傳感器資料按時間序列存儲,為同步的時間點找到相應的位置;
2.即找到相應時刻的相鄰兩個資料;
3.值得注意的是相鄰資料有一個離同步的時刻間隔太遠,證明有資料的丢失,時間間隔太遠則不适合進行插值;
算法邏輯:(t0, t1,t,tx:更新頻率)
1.對資料進行周遊處理,直到找到同步時刻相鄰的資料; 若隊列小于2,仍未找到,則結束周遊
2. 如果t0 > t 則直接傳回false, 不然就滿足了 t0 < t;如果 t1 < t 則将隊首元素彈出,直到找到t < t1;如果t-t0 >tx**,則彈出t0,**并結束;如果t1 - t >tx ,則傳回并退出;
3. 找到相鄰兩元素後,進行線性插值計算:
2.GNSS的訂閱子產品
頭檔案:
-
List itemGNSSSubscriber() = default; 什麼用法?
=default 預設構造函數, =delete 禁用成員函數的使用
#ifndef LIDAR_LOCALIZATION_SUBSCRIBER_GNSS_SUBSCRIBER_HPP_
#define LIDAR_LOCALIZATION_SUBSCRIBER_GNSS_SUBSCRIBER_HPP_
#include <ros/ros.h>
#include "sersor_msgs/NavSatFix.h"
#include "lidar_localization/sensor_data/gnss_data.hpp"
#include <deque>
namespace lidar_localization {
class GNSSSubscriber{
public:
GNSSSubscriber(ros::NodeHandle& nh, std::string Topic_name, size_t buff_size);
GNSSSubscriber() = default;//預設構造函數
void ParseData (std::deque<GNSSData>& deque_gnss_data);
private:
void msg_callback (const sensor_msgs::NavSatFixPtr& nav_sat_fix_ptr);
private:
ros::NodeHandle nh_;
ros::Subscriber subscriber_;
std::deque<GNSSData> new_gnss_data;
};
}
#endif // !LIDAR_LOCALIZATION_SUBSCRIBER_GNSS_SUBSCRIBER_HPP
源檔案:
#include "lidar_localization/subscriber/gnss_subscriber.hpp"
#include "glog/logging.h"
namespace lidar_localization {
GNSSSubscriber::GNSSSubscriber(ros::NodeHandle& nh, std::string topic_name, size_t buff_size)
:nh_(nh) {
subscriber_ = nh_.subscribe(topic_name, buff_size, &GNSSSubscriber::msg_callback, this);
}
void GNSSSubscriber::msg_callback(const sensor_msgs::NavSatFixConstPtr& nav_sat_fix_ptr) {
GNSSData gnss_data;
gnss_data.time = nav_sat_fix_ptr->header.stamp.toSec();
gnss_data.latitude = nav_sat_fix_ptr->latitude;
gnss_data.longitude = nav_sat_fix_ptr->longitude;
gnss_data.altitude = nav_sat_fix_ptr->altitude;
gnss_data.status = nav_sat_fix_ptr->status.status;
gnss_data.service = nav_sat_fix_ptr->status.service;
new_gnss_data_.push_back(gnss_data);
}
void GNSSSubscriber::ParseData(std::deque<GNSSData>& gnss_data_buff) {
if (new_gnss_data_.size() > 0) {
gnss_data_buff.insert(gnss_data_buff.end(), new_gnss_data_.begin(), new_gnss_data_.end());
new_gnss_data_.clear();
}
}
}
其中:ParseData函數是用來讀取接收到的傳感器資料,類似于緩沖區
三、點雲子產品
1.CloudData資料結構
-
using = ?
通過using指定别名