Apollo 10.0
自动驾驶开放平台
localization_params.h
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
22#pragma once
23
24#include <string>
25
26#include "modules/common_msgs/localization_msgs/localization.pb.h"
27
32namespace apollo {
33namespace localization {
34namespace msf {
35
38 : offset_x(0.0),
39 offset_y(0.0),
40 offset_z(0.0),
41 uncertainty_x(0.0),
42 uncertainty_y(0.0),
43 uncertainty_z(0.0) {}
44 double offset_x;
45 double offset_y;
46 double offset_z;
50};
51
53 VehicleToImuQuatern() : x(0.0), y(0.0), z(0.0), w(1.0) {}
54 double x;
55 double y;
56 double z;
57 double w;
58};
59
61 // localization mode
63 int gnss_mode = 0;
64
65 // sins module
68 bool is_sins_state_check = false;
69 double sins_state_span_time = 60.0;
70 double sins_state_pos_std = 1.0;
74
75 // gnss module
76 bool enable_ins_aid_rtk = false;
78
79 // lidar module
80 std::string map_path = "";
81 std::string lidar_extrinsic_file = "";
82 std::string lidar_height_file = "";
89 int utm_zone_id = 50;
92 bool if_use_avx = false;
93
95 std::string ant_imu_leverarm_file = "";
97
98 // localization status param
102
106
109
112
115};
116
118 OK = 0,
119 WARNNING,
120 ERROR,
123};
128
130
132 public:
136 const LocalizationEstimate& localiztion,
138 : state_(state),
139 localization_(localiztion),
140 integ_status_(integ_status) {}
141 LocalizationMeasureState state() const { return state_; }
142 LocalizationEstimate localization() const { return localization_; }
143 LocalizationIntegStatus integ_status() const { return integ_status_; }
144
145 private:
147 LocalizationEstimate localization_;
148 LocalizationIntegStatus integ_status_;
149};
150
151} // namespace msf
152} // namespace localization
153} // namespace apollo
LocalizationResult(const LocalizationMeasureState &state, const LocalizationEstimate &localiztion, const LocalizationIntegStatus &integ_status=LocalizationIntegStatus())
class register implement
Definition arena_queue.h:37