Apollo 10.0
自动驾驶开放平台
apollo::drivers::gnss 命名空间参考

命名空间

namespace  config
 
namespace  enbroad
 
namespace  novatel
 

class  AsensingParser
 
struct  BandObservation
 
struct  BraodGnss101BMessage
 
class  BroadGnssBaseParser
 
struct  BroadGnssMessage
 
class  BroadGnssTextParser
 
struct  BroadGnssTextProtocol
 
class  CanStream
 
class  DataParser
 
class  EnbroadParse
 
struct  EpochObservation
 
class  ForsenseBaseParser
 
struct  ForsenseMessage
 
struct  ForsenseProtocol
 
class  ForsenseTextParser
 
struct  GlonassOrbit
 
struct  Gnss
 
struct  GnssBestPose
 
class  GnssDriverComponent
 
struct  GnssEphemeris
 
struct  GnssStatus
 
struct  Heading
 
class  HuaCeBaseParser
 
struct  HuaCeMessage
 
struct  HuaCeProtocol
 
class  HuaCeTextParser
 
struct  Imu
 
struct  Ins
 
struct  InsStat
 
struct  InsStatus
 
struct  KepplerOrbit
 
struct  MessageInfo
 
class  NovatelParser
 
class  NtripStream
 
class  Parser
 
class  RateControl
 
struct  RawData
 
class  RawStream
 
class  Rtcm3Parser
 
class  RtcmParser
 
struct  SatelliteObservation
 
class  SerialStream
 
class  Stream
 
struct  StreamStatus
 
class  TcpStream
 
class  UdpStream
 

类型定义

using MessagePtr = ::google::protobuf::Message *
 
using MessageInfoVec = std::vector< MessageInfo >
 

枚举

enum  SolutionStatus {
  SOL_COMPUTED = 0 , INSUFFICIENT_OBS = 1 , NO_CONVERGENCE = 2 , SINGULARITY = 3 ,
  COV_TRACE = 4 , TEST_DIST = 5 , COLD_START = 6 , V_H_LIMIT = 7 ,
  VARIANCE = 8 , RESIDUALS = 9 , INTEGRITY_WARNING = 13 , PENDING = 18 ,
  INVALID_FIX = 19 , UNAUTHORIZED = 20 , INVALID_RATE = 22
}
 
enum  SolutionType {
  NONE = 0 , FIXEDPOS = 1 , FIXEDHEIGHT = 2 , FLOATCONV = 4 ,
  WIDELANE = 5 , NARROWLANE = 6 , DOPPLER_VELOCITY = 8 , SINGLE = 16 ,
  PSRDIFF = 17 , WAAS = 18 , PROPOGATED = 19 , OMNISTAR = 20 ,
  L1_FLOAT = 32 , IONOFREE_FLOAT = 33 , NARROW_FLOAT = 34 , L1_INT = 48 ,
  WIDE_INT = 49 , NARROW_INT = 50 , RTK_DIRECT_INS = 51 , INS_SBAS = 52 ,
  INS_PSRSP = 53 , INS_PSRDIFF = 54 , INS_RTKFLOAT = 55 , INS_RTKFIXED = 56 ,
  INS_OMNISTAR = 57 , INS_OMNISTAR_HP = 58 , INS_OMNISTAR_XP = 59 , OMNISTAR_HP = 64 ,
  OMNISTAR_XP = 65 , PPP_CONVERGING = 68 , PPP = 69 , INS_PPP_CONVERGING = 73 ,
  INS_PPP = 74
}
 
enum  DatumId { WGS84 = 61 }
 
enum  GnssBandID {
  BAND_UNKNOWN = 0 , GPS_L1 = 1 , GPS_L2 = 2 , GPS_L5 = 3 ,
  BDS_B1 = 4 , BDS_B2 = 5 , BDS_B3 = 6 , GLO_G1 = 7 ,
  GLO_G2 = 8 , GLO_G3 = 9
}
 
enum  GnssTimeType {
  TIME_UNKNOWN = 0 , GPS_TIME = 1 , BDS_TIME = 2 , GLO_TIME = 3 ,
  GAL_TIME = 4
}
 
enum  GnssType {
  SYS_UNKNOWN = 0 , GPS_SYS = 1 , BDS_SYS = 2 , GLO_SYS = 3 ,
  GAL_SYS = 4
}
 
enum  PseudoType { CODE_UNKNOWN = 0 , CORSE_CODE = 1 , PRECISION_CODE = 2 }
 
enum class  MessageType {
  NONE , GNSS , GNSS_RANGE , IMU ,
  INS , INS_STAT , WHEEL , EPHEMERIDES ,
  OBSERVATION , GPGGA , BDSEPHEMERIDES , RAWIMU ,
  GPSEPHEMERIDES , GLOEPHEMERIDES , BEST_GNSS_POS , HEADING
}
 

函数

double normalizeAngleTo180 (double angle)
 
template<class T >
T * As (::google::protobuf::Message *message_ptr)
 
constexpr double azimuth_deg_to_yaw_rad (double azimuth)
 
void rfu_to_flu (double r, double f, double u, ::apollo::common::Point3D *flu)
 
void switch_stream_status (const apollo::drivers::gnss::Stream::Status &status, StreamStatus_Type *report_status_type)
 
std::string getLocalTimeFileStr (const std::string &gpsbin_folder)
 
Streamcreate_stream (const config::Stream &sd)
 
speed_t get_serial_baudrate (uint32_t rate)
 
void ParseBin (const char *filename, DataParser *parser)
 
void ParseRecord (const char *filename, DataParser *parser)
 
void Parse (const char *filename, const char *file_type, const std::shared_ptr<::apollo::cyber::Node > &node)
 

变量

constexpr uint32_t Message101B_ID = 0x553ACE02
 
constexpr size_t BUFFER_SIZE = 256
 
constexpr int SECONDS_PER_WEEK = 60 * 60 * 24 * 7
 
constexpr double DEG_TO_RAD = M_PI / 180.0
 
constexpr double EPS = 1e-8
 
constexpr float FLOAT_NAN = std::numeric_limits<float>::quiet_NaN()
 
constexpr uint64_t PERIOD_NS_1HZ = 900 * 1e6
 

类型定义说明

◆ MessageInfoVec

using apollo::drivers::gnss::MessageInfoVec = typedef std::vector<MessageInfo>

在文件 parser.h57 行定义.

◆ MessagePtr

using apollo::drivers::gnss::MessagePtr = typedef ::google::protobuf::Message *

在文件 parser.h34 行定义.

枚举类型说明

◆ DatumId

枚举值
WGS84 

在文件 gnss_best_pose.proto64 行定义.

66 {
67 // We only use WGS-84.

◆ GnssBandID

◆ GnssTimeType

◆ GnssType

◆ MessageType

枚举值
NONE 
GNSS 
GNSS_RANGE 
IMU 
INS 
INS_STAT 
WHEEL 
EPHEMERIDES 
OBSERVATION 
GPGGA 
BDSEPHEMERIDES 
RAWIMU 
GPSEPHEMERIDES 
GLOEPHEMERIDES 
BEST_GNSS_POS 
HEADING 

在文件 parser.h35 行定义.

◆ PseudoType

枚举值
CODE_UNKNOWN 
CORSE_CODE 
PRECISION_CODE 

在文件 gnss_raw_observation.proto39 行定义.

◆ SolutionStatus

枚举值
SOL_COMPUTED 
INSUFFICIENT_OBS 
NO_CONVERGENCE 
SINGULARITY 
COV_TRACE 
TEST_DIST 
COLD_START 
V_H_LIMIT 
VARIANCE 
RESIDUALS 
INTEGRITY_WARNING 
PENDING 
INVALID_FIX 
UNAUTHORIZED 
INVALID_RATE 

在文件 gnss_best_pose.proto7 行定义.

7 {
8 SOL_COMPUTED = 0; // solution computed
9 INSUFFICIENT_OBS = 1; // insufficient observations
10 NO_CONVERGENCE = 2; // no convergence
11 SINGULARITY = 3; // singularity at parameters matrix
12 COV_TRACE = 4; // covariance trace exceeds maximum (trace > 1000 m)
13 TEST_DIST = 5; // test distance exceeded (max of 3 rejections if distance >
14 // 10 km)
15 COLD_START = 6; // not yet converged from cold start
16 V_H_LIMIT = 7; // height or velocity limits exceeded
17 VARIANCE = 8; // variance exceeds limits
18 RESIDUALS = 9; // residuals are too large
19 INTEGRITY_WARNING = 13; // large residuals make position questionable
20 PENDING = 18; // receiver computes its position and determines if the fixed
21 // position is valid
22 INVALID_FIX = 19; // the fixed position entered using the fix position
23 // command is invalid
24 UNAUTHORIZED = 20; // position type is unauthorized
26 22; // selected logging rate is not supported for this solution type

◆ SolutionType

枚举值
NONE 
FIXEDPOS 
FIXEDHEIGHT 
FLOATCONV 
WIDELANE 
NARROWLANE 
DOPPLER_VELOCITY 
SINGLE 
PSRDIFF 
WAAS 
PROPOGATED 
OMNISTAR 
L1_FLOAT 
IONOFREE_FLOAT 
NARROW_FLOAT 
L1_INT 
WIDE_INT 
NARROW_INT 
RTK_DIRECT_INS 
INS_SBAS 
INS_PSRSP 
INS_PSRDIFF 
INS_RTKFLOAT 
INS_RTKFIXED 
INS_OMNISTAR 
INS_OMNISTAR_HP 
INS_OMNISTAR_XP 
OMNISTAR_HP 
OMNISTAR_XP 
PPP_CONVERGING 
PPP 
INS_PPP_CONVERGING 
INS_PPP 

在文件 gnss_best_pose.proto28 行定义.

29 {
30 NONE = 0;
31 FIXEDPOS = 1;
32 FIXEDHEIGHT = 2;
33 FLOATCONV = 4;
34 WIDELANE = 5;
35 NARROWLANE = 6;
36 DOPPLER_VELOCITY = 8;
37 SINGLE = 16;
38 PSRDIFF = 17;
39 WAAS = 18;
40 PROPOGATED = 19;
41 OMNISTAR = 20;
42 L1_FLOAT = 32;
43 IONOFREE_FLOAT = 33;
44 NARROW_FLOAT = 34;
45 L1_INT = 48;
46 WIDE_INT = 49;
47 NARROW_INT = 50;
48 RTK_DIRECT_INS =
49 51; // RTK filter is directly initialized from the INS filter.
50 INS_SBAS = 52;
51 INS_PSRSP = 53;
52 INS_PSRDIFF = 54;
53 INS_RTKFLOAT = 55;
54 INS_RTKFIXED = 56;
55 INS_OMNISTAR = 57;
56 INS_OMNISTAR_HP = 58;
57 INS_OMNISTAR_XP = 59;
58 OMNISTAR_HP = 64;
59 OMNISTAR_XP = 65;
60 PPP_CONVERGING = 68;
61 PPP = 69;

函数说明

◆ As()

template<class T >
T * apollo::drivers::gnss::As ( ::google::protobuf::Message *  message_ptr)
inline

在文件 parser.h72 行定义.

72 {
73 return dynamic_cast<T *>(message_ptr);
74}

◆ azimuth_deg_to_yaw_rad()

constexpr double apollo::drivers::gnss::azimuth_deg_to_yaw_rad ( double  azimuth)
constexpr

在文件 parser_common.h38 行定义.

38 {
39 return (90.0 - azimuth) * DEG_TO_RAD;
40}
#define DEG_TO_RAD

◆ create_stream()

Stream * apollo::drivers::gnss::create_stream ( const config::Stream sd)

在文件 raw_stream.cc73 行定义.

73 {
74 switch (sd.type_case()) {
75 case config::Stream::kSerial:
76 if (!sd.serial().has_device()) {
77 AERROR << "Serial def has no device field.";
78 return nullptr;
79 }
80 if (!sd.serial().has_baud_rate()) {
81 AERROR << "Serial def has no baud_rate field. Use default baud rate "
82 << sd.serial().baud_rate();
83 return nullptr;
84 }
85 return Stream::create_serial(sd.serial().device().c_str(),
86 sd.serial().baud_rate());
87
88 case config::Stream::kTcp:
89 if (!sd.tcp().has_address()) {
90 AERROR << "tcp def has no address field.";
91 return nullptr;
92 }
93 if (!sd.tcp().has_port()) {
94 AERROR << "tcp def has no port field.";
95 return nullptr;
96 }
97 return Stream::create_tcp(sd.tcp().address().c_str(),
98 static_cast<uint16_t>(sd.tcp().port()));
99
100 case config::Stream::kUdp:
101 if (!sd.udp().has_address()) {
102 AERROR << "tcp def has no address field.";
103 return nullptr;
104 }
105 if (!sd.udp().has_port()) {
106 AERROR << "tcp def has no port field.";
107 return nullptr;
108 }
109 return Stream::create_udp(sd.udp().address().c_str(),
110 static_cast<uint16_t>(sd.udp().port()));
111
112 case config::Stream::kNtrip:
113 if (!sd.ntrip().has_address()) {
114 AERROR << "ntrip def has no address field.";
115 return nullptr;
116 }
117 if (!sd.ntrip().has_port()) {
118 AERROR << "ntrip def has no port field.";
119 return nullptr;
120 }
121 if (!sd.ntrip().has_mount_point()) {
122 AERROR << "ntrip def has no mount point field.";
123 return nullptr;
124 }
125 if (!sd.ntrip().has_user()) {
126 AERROR << "ntrip def has no user field.";
127 return nullptr;
128 }
129 if (!sd.ntrip().has_password()) {
130 AERROR << "ntrip def has no passwd field.";
131 return nullptr;
132 }
133 return Stream::create_ntrip(
134 sd.ntrip().address(), static_cast<uint16_t>(sd.ntrip().port()),
135 sd.ntrip().mount_point(), sd.ntrip().user(), sd.ntrip().password(),
136 sd.ntrip().timeout_s());
137 case config::Stream::kCanCardParameter:
138 if (!sd.can_card_parameter().has_brand()) {
139 AERROR << "can_card_parameter def has no brand field.";
140 return nullptr;
141 }
142 if (!sd.can_card_parameter().has_type()) {
143 AERROR << "can_card_parameter def has no type field.";
144 return nullptr;
145 }
146 if (!sd.can_card_parameter().has_channel_id()) {
147 AERROR << "can_card_parameter def has no channel_id field.";
148 return nullptr;
149 }
150 if (!sd.can_card_parameter().has_channel_id()) {
151 AERROR << "can_card_parameter def has no channel_id field.";
152 return nullptr;
153 }
154 return Stream::create_can(sd.can_card_parameter());
155 default:
156 return nullptr;
157 }
158}
#define AERROR
Definition log.h:44

◆ get_serial_baudrate()

speed_t apollo::drivers::gnss::get_serial_baudrate ( uint32_t  rate)

在文件 serial_stream.cc39 行定义.

39 {
40 switch (rate) {
41 case 9600:
42 return B9600;
43 case 19200:
44 return B19200;
45 case 38400:
46 return B38400;
47 case 57600:
48 return B57600;
49 case 115200:
50 return B115200;
51 case 230400:
52 return B230400;
53 case 460800:
54 return B460800;
55 case 921600:
56 return B921600;
57 default:
58 return 0;
59 }
60}

◆ getLocalTimeFileStr()

std::string apollo::drivers::gnss::getLocalTimeFileStr ( const std::string &  gpsbin_folder)

在文件 raw_stream.cc57 行定义.

57 {
58 time_t it = std::time(0);
59 char local_time_char[64];
60 std::tm time_tm;
61 localtime_r(&it, &time_tm);
62
63 std::strftime(local_time_char, sizeof(local_time_char), "%Y%m%d_%H%M%S",
64 &time_tm);
65 std::string local_time_str = local_time_char;
66 ACHECK(cyber::common::EnsureDirectory(gpsbin_folder))
67 << "gbsbin folder : " << gpsbin_folder << " create fail";
68 std::string local_time_file_str =
69 gpsbin_folder + "/" + local_time_str + ".bin";
70 return local_time_file_str;
71}
#define ACHECK(cond)
Definition log.h:80

◆ normalizeAngleTo180()

double apollo::drivers::gnss::normalizeAngleTo180 ( double  angle)

在文件 enbroad_parser.cc152 行定义.

152 {
153 while (angle > 180.0) {
154 angle -= 360.0;
155 }
156 while (angle <= -180.0) {
157 angle += 360.0;
158 }
159 return angle;
160}

◆ Parse()

void apollo::drivers::gnss::Parse ( const char *  filename,
const char *  file_type,
const std::shared_ptr<::apollo::cyber::Node > &  node 
)

在文件 parser_cli.cc63 行定义.

64 {
65 std::string type = std::string(file_type);
66 config::Config config;
68 std::string("modules/drivers/gnss/conf/gnss_conf.pb.txt"),
69 &config)) {
70 std::cout << "Unable to load gnss conf file";
71 }
72 DataParser* parser = new DataParser(config, node);
73 parser->Init();
74 if (type == "bin") {
75 ParseBin(filename, parser);
76 } else if (type == "record") {
77 ParseRecord(filename, parser);
78 } else {
79 std::cout << "unknown file type";
80 }
81 delete parser;
82}
bool GetProtoFromFile(const std::string &file_name, google::protobuf::Message *message)
Parses the content of the file specified by the file_name as a representation of protobufs,...
Definition file.cc:132

◆ ParseBin()

void apollo::drivers::gnss::ParseBin ( const char *  filename,
DataParser parser 
)

在文件 parser_cli.cc39 行定义.

39 {
40 std::ios::sync_with_stdio(false);
41 std::ifstream f(filename, std::ifstream::binary);
42 char b[BUFFER_SIZE];
43 while (f && cyber::OK()) {
44 f.read(b, BUFFER_SIZE);
45 std::string msg(reinterpret_cast<const char*>(b), f.gcount());
46 parser->ParseRawData(msg);
47 }
48}
double f
void ParseRawData(const std::string &msg)
constexpr size_t BUFFER_SIZE

◆ ParseRecord()

void apollo::drivers::gnss::ParseRecord ( const char *  filename,
DataParser parser 
)

在文件 parser_cli.cc50 行定义.

50 {
51 cyber::record::RecordReader reader(filename);
53 while (reader.ReadMessage(&message) && cyber::OK()) {
54 if (message.channel_name == "/apollo/sensor/gnss/raw_data") {
56 msg.ParseFromString(message.content);
57 parser->ParseRawData(msg.data());
58 }
59 std::this_thread::sleep_for(std::chrono::milliseconds(2));
60 }
61}
Basic data struct of record message.
std::string content
The content of the message.
std::string channel_name
The channel name of the message.

◆ rfu_to_flu()

void apollo::drivers::gnss::rfu_to_flu ( double  r,
double  f,
double  u,
::apollo::common::Point3D flu 
)
inline

在文件 parser_common.h44 行定义.

45 {
46 flu->set_x(f);
47 flu->set_y(-r);
48 flu->set_z(u);
49}

◆ switch_stream_status()

void apollo::drivers::gnss::switch_stream_status ( const apollo::drivers::gnss::Stream::Status status,
StreamStatus_Type *  report_status_type 
)

在文件 raw_stream.cc40 行定义.

41 {
42 switch (status) {
44 *report_status_type = StreamStatus::CONNECTED;
45 break;
46
48 *report_status_type = StreamStatus::DISCONNECTED;
49 break;
50
52 default:
53 *report_status_type = StreamStatus::DISCONNECTED;
54 break;
55 }
56}

变量说明

◆ BUFFER_SIZE

constexpr size_t apollo::drivers::gnss::BUFFER_SIZE = 256
constexpr

在文件 enbroad_parser.cc55 行定义.

◆ DEG_TO_RAD

constexpr double apollo::drivers::gnss::DEG_TO_RAD = M_PI / 180.0
constexpr

在文件 parser_common.h32 行定义.

◆ EPS

constexpr double apollo::drivers::gnss::EPS = 1e-8
constexpr

在文件 parser_common.h34 行定义.

◆ FLOAT_NAN

constexpr float apollo::drivers::gnss::FLOAT_NAN = std::numeric_limits<float>::quiet_NaN()
constexpr

在文件 parser_common.h36 行定义.

◆ Message101B_ID

constexpr uint32_t apollo::drivers::gnss::Message101B_ID = 0x553ACE02
constexpr

在文件 broadgnss_message.h28 行定义.

◆ PERIOD_NS_1HZ

constexpr uint64_t apollo::drivers::gnss::PERIOD_NS_1HZ = 900 * 1e6
constexpr

在文件 parser_common.h51 行定义.

◆ SECONDS_PER_WEEK

constexpr int apollo::drivers::gnss::SECONDS_PER_WEEK = 60 * 60 * 24 * 7
constexpr

在文件 parser_common.h30 行定义.