Apollo
10.0
自动驾驶开放平台
pose.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/geometry.proto
";
22
23
message
Pose
{
24
// Position of the vehicle reference point (VRP) in the map reference frame.
25
// The VRP is the center of rear axle.
26
optional
apollo
.
common
.
PointENU
position = 1;
27
28
// A quaternion that represents the rotation from the IMU coordinate
29
// (Right/Forward/Up) to the
30
// world coordinate (East/North/Up).
31
optional
apollo
.
common
.
Quaternion
orientation = 2;
32
33
// Linear velocity of the VRP in the map reference frame.
34
// East/north/up in meters per second.
35
optional
apollo
.
common
.
Point3D
linear_velocity = 3;
36
37
// Linear acceleration of the VRP in the map reference frame.
38
// East/north/up in meters per square second.
39
optional
apollo
.
common
.
Point3D
linear_acceleration = 4;
40
41
// Angular velocity of the vehicle in the map reference frame.
42
// Around east/north/up axes in radians per second.
43
optional
apollo
.
common
.
Point3D
angular_velocity = 5;
44
45
// Heading
46
// The heading is zero when the car is facing East and positive when facing
47
// North.
48
optional
double
heading = 6;
49
50
// Linear acceleration of the VRP in the vehicle reference frame.
51
// Right/forward/up in meters per square second.
52
optional
apollo
.
common
.
Point3D
linear_acceleration_vrf = 7;
53
54
// Angular velocity of the VRP in the vehicle reference frame.
55
// Around right/forward/up axes in radians per second.
56
optional
apollo
.
common
.
Point3D
angular_velocity_vrf = 8;
57
58
// Roll/pitch/yaw that represents a rotation with intrinsic sequence z-x-y.
59
// in world coordinate (East/North/Up)
60
// The roll, in (-pi/2, pi/2), corresponds to a rotation around the y-axis.
61
// The pitch, in [-pi, pi), corresponds to a rotation around the x-axis.
62
// The yaw, in [-pi, pi), corresponds to a rotation around the z-axis.
63
// The direction of rotation follows the right-hand rule.
64
optional
apollo
.
common
.
Point3D
euler_angles = 9;
65
}
geometry.proto
apollo::common
apollo::common
apollo
class register implement
Definition
arena_queue.h:37
syntax
syntax
Definition
pose.proto:17
apollo::common::Point3D
Definition
geometry.proto:41
apollo::common::PointENU
Definition
geometry.proto:14
apollo::common::Quaternion
Definition
geometry.proto:52
apollo::localization::Pose
Definition
pose.proto:23
modules
common_msgs
localization_msgs
pose.proto