Apollo 11.0
自动驾驶开放平台
third_party_perception_util.h
浏览该文件的文档.
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
21#pragma once
22
23#include "modules/common_msgs/perception_msgs/perception_obstacle.pb.h"
24
30namespace apollo {
31namespace third_party_perception {
32
34
36 apollo::perception::PerceptionObstacle* const perception_obstacle,
37 const double mid_x, const double mid_y, const double mid_z,
38 const double length, const double width, const double height,
39 const double heading);
40
41// TODO(lizh): change it to PerceptionObstacle::VEHICLE or so
42// when perception obstacle type is extended.
43// object type | int
44// car | 0
45// truck | 1
46// bike | 2
47// ped | 3
48// unknown | 4
49double GetDefaultObjectLength(const int object_type);
50
51double GetDefaultObjectWidth(const int object_type);
52
53apollo::common::Point3D SLtoXY(const double x, const double y,
54 const double theta);
55
57 const double theta);
58
59double Distance(const apollo::common::Point3D& point1,
60 const apollo::common::Point3D& point2);
61
62double Speed(const apollo::common::Point3D& point);
63
64double Speed(const double vx, const double vy);
65
66double GetNearestLaneHeading(const apollo::common::PointENU& point_enu);
67
69
70double GetNearestLaneHeading(const double x, const double y, const double z);
71
73
74double HeadingDifference(const double theta1, const double theta2);
75
76} // namespace third_party_perception
77} // namespace apollo
void FillPerceptionPolygon(PerceptionObstacle *const perception_obstacle, const double mid_x, const double mid_y, const double mid_z, const double length, const double width, const double height, const double heading)
double GetDefaultObjectLength(const int object_type)
double GetAngleFromQuaternion(const Quaternion quaternion)
double Distance(const Point &point1, const Point &point2)
double GetLateralDistanceToNearestLane(const Point &point)
Point SLtoXY(const Point &point, const double theta)
double HeadingDifference(const double theta1, const double theta2)
double GetNearestLaneHeading(const PointENU &point_enu)
double GetDefaultObjectWidth(const int object_type)
class register implement
Definition arena_queue.h:37