Apollo
10.0
自动驾驶开放平台
free_space_command.proto
浏览该文件的文档.
1
syntax
=
"proto2"
;
2
3
package
apollo.external_command;
4
5
import
"
modules/common_msgs/basic_msgs/header.proto
";
6
import
"
modules/common_msgs/external_command_msgs/geometry.proto
";
7
8
message
FreeSpaceCommand
{
9
optional
apollo
.
common
.
Header
header = 1;
10
// Unique identification for command.
11
optional int64 command_id = 2 [
default
= -1];
12
// Pose of the parking spot.
13
required
Pose
parking_spot_pose = 3;
14
// Region where openspace trajectory will be searched. Junction containing
15
// "non_drivable_roi" should be contained by "drivable_roi"
16
// polygon points should be clockwise if outer polygon can drive.
17
// otherwise polygon points should be counter-clockwise if inner polygon can drive
18
repeated
RoiPolygon
non_drivable_roi = 4;
19
required
RoiPolygon
drivable_roi = 5;
20
// Expected speed when executing this command. If "target_speed" > maximum
21
// speed of the vehicle, use maximum speed of the vehicle instead. If it is
22
// not given, the default target speed of system will be used.
23
optional
double
target_speed = 6;
24
}
geometry.proto
syntax
syntax
Definition
free_space_command.proto:1
header.proto
apollo::common
apollo::common
apollo
class register implement
Definition
arena_queue.h:37
apollo::common::Header
Definition
header.proto:7
apollo::external_command::FreeSpaceCommand
Definition
free_space_command.proto:8
apollo::external_command::Pose
Definition
geometry.proto:12
apollo::external_command::RoiPolygon
Definition
geometry.proto:24
modules
common_msgs
external_command_msgs
free_space_command.proto