Apollo
10.0
自动驾驶开放平台
localization.proto
浏览该文件的文档.
1
/******************************************************************************
2
* Copyright 2017 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
17
syntax
=
"proto2"
;
18
19
package
apollo.localization;
20
21
import
"
modules/common_msgs/basic_msgs/header.proto
";
22
import
"
modules/common_msgs/basic_msgs/geometry.proto
";
23
import
"
modules/common_msgs/basic_msgs/pnc_point.proto
";
24
import
"
modules/common_msgs/localization_msgs/localization_status.proto
";
25
import
"
modules/common_msgs/localization_msgs/pose.proto
";
26
27
message
Uncertainty
{
28
// Standard deviation of position, east/north/up in meters.
29
optional
apollo
.
common
.
Point3D
position_std_dev = 1;
30
31
// Standard deviation of quaternion qx/qy/qz, unitless.
32
optional
apollo
.
common
.
Point3D
orientation_std_dev = 2;
33
34
// Standard deviation of linear velocity, east/north/up in meters per second.
35
optional
apollo
.
common
.
Point3D
linear_velocity_std_dev = 3;
36
37
// Standard deviation of linear acceleration, right/forward/up in meters per
38
// square second.
39
optional
apollo
.
common
.
Point3D
linear_acceleration_std_dev = 4;
40
41
// Standard deviation of angular velocity, right/forward/up in radians per
42
// second.
43
optional
apollo
.
common
.
Point3D
angular_velocity_std_dev = 5;
44
45
// TODO: Define covariance items when needed.
46
}
47
48
message
LocalizationEstimate
{
49
optional
apollo
.
common
.
Header
header = 1;
50
optional
apollo
.
localization
.
Pose
pose = 2;
51
optional
Uncertainty
uncertainty = 3;
52
53
// The time of pose measurement, seconds since 1970-1-1 (UNIX time).
54
optional
double
measurement_time = 4;
// In seconds.
55
56
// Future trajectory actually driven by the drivers
57
repeated
apollo
.
common
.
TrajectoryPoint
trajectory_point = 5;
58
59
// msf status
60
optional
MsfStatus
msf_status = 6;
61
// msf quality
62
optional
MsfSensorMsgStatus
sensor_status = 7;
63
}
64
65
enum
MeasureState
{
66
OK
= 0;
67
WARNNING
= 1;
68
ERROR
= 2;
69
CRITICAL_ERROR
= 3;
70
FATAL_ERROR
= 4;
71
}
72
73
message
LocalizationStatus
{
74
optional
apollo
.
common
.
Header
header = 1;
75
optional
MeasureState
fusion_status = 2;
76
optional
MeasureState
gnss_status = 3 [deprecated =
true
];
77
optional
MeasureState
lidar_status = 4 [deprecated =
true
];
78
// The time of pose measurement, seconds since 1970-1-1 (UNIX time).
79
optional
double
measurement_time = 5;
// In seconds.
80
optional
string
state_message = 6;
81
}
geometry.proto
header.proto
syntax
syntax
Definition
localization.proto:17
localization_status.proto
apollo::common
apollo::common
apollo::localization
apollo::localization
Definition
gps.proto:3
apollo::localization::MeasureState
MeasureState
Definition
localization.proto:65
apollo::localization::FATAL_ERROR
@ FATAL_ERROR
Definition
localization.proto:70
apollo::localization::WARNNING
@ WARNNING
Definition
localization.proto:67
apollo::localization::CRITICAL_ERROR
@ CRITICAL_ERROR
Definition
localization.proto:69
apollo::localization::ERROR
@ ERROR
Definition
localization.proto:68
apollo::localization::OK
@ OK
Definition
localization.proto:66
apollo
class register implement
Definition
arena_queue.h:37
pnc_point.proto
pose.proto
apollo::common::Header
Definition
header.proto:7
apollo::common::Point3D
Definition
geometry.proto:41
apollo::common::TrajectoryPoint
Definition
pnc_point.proto:61
apollo::localization::LocalizationEstimate
Definition
localization.proto:48
apollo::localization::LocalizationStatus
Definition
localization.proto:73
apollo::localization::MsfSensorMsgStatus
Definition
localization_status.proto:155
apollo::localization::MsfStatus
Definition
localization_status.proto:219
apollo::localization::Pose
Definition
pose.proto:23
apollo::localization::Uncertainty
Definition
localization.proto:27
modules
common_msgs
localization_msgs
localization.proto