Apollo 10.0
自动驾驶开放平台
map_service.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 <string>
24#include <vector>
25
26#include <boost/thread/locks.hpp>
27#include <boost/thread/shared_mutex.hpp>
28
29#include "nlohmann/json.hpp"
30
31#include "modules/common_msgs/dreamview_msgs/simulation_world.pb.h"
32#include "modules/common_msgs/routing_msgs/routing.pb.h"
33
35
40namespace apollo {
41namespace dreamview {
42
44 public:
45 explicit MapService(bool use_sim_map = true);
46
47 inline double GetXOffset() const { return x_offset_; }
48 inline double GetYOffset() const { return y_offset_; }
49
50 bool PointIsValid(const double x, const double y) const;
51
53 double raidus, MapElementIds *ids) const;
54
57 std::vector<apollo::hdmap::Path> *paths) const;
58
59 // The returned value is of a hdmap::Map proto. This
60 // makes it easy to convert to a JSON object and to send to the
61 // javascript clients.
63
64 bool GetPoseWithRegardToLane(const double x, const double y, double *theta,
65 double *s) const;
66
67 // Get a point on the map to serve as dummy start point of SimControl
68 bool GetStartPoint(apollo::common::PointENU *start_point) const;
69
78 bool ConstructLaneWayPoint(const double x, const double y,
79 routing::LaneWaypoint *laneWayPoint) const;
80
82 const double x, const double y, const double heading,
83 routing::LaneWaypoint *laneWayPoint) const;
84
86 const double x, const double y, const std::string id,
87 routing::LaneWaypoint *laneWayPoint) const;
88
89 bool CheckRoutingPoint(const double x, const double y) const;
90
91 bool CheckRoutingPointWithHeading(const double x, const double y,
92 const double heading) const;
93
95
96 // Reload map from current FLAGS_map_dir.
97 bool ReloadMap(bool force_reload);
98
99 size_t CalculateMapHash(const MapElementIds &ids) const;
100
101 double GetLaneHeading(const std::string &id_str, double s);
102
103 std::string GetParkingSpaceId(const double x, const double y) const;
104
105 private:
106 void UpdateOffsets();
107
108 bool GetNearestLaneWithDistance(const double x, const double y,
110 double *nearest_s, double *nearest_l) const;
111
112 bool GetNearestLane(const double x, const double y,
114 double *nearest_s, double *nearest_l) const;
115
116 bool GetNearestLaneWithHeading(const double x, const double y,
118 double *nearest_s, double *nearest_l,
119 const double heading) const;
120
121 bool CreatePathsFromRouting(
122 const routing::RoutingResponse &routing,
123 std::vector<apollo::hdmap::Path> *paths) const;
124
125 bool AddPathFromPassageRegion(const routing::Passage &passage_region,
126 std::vector<apollo::hdmap::Path> *paths) const;
127
128 static const char kMetaFileName[];
129
130 const bool use_sim_map_;
131 const hdmap::HDMap *HDMap() const;
132 // A downsampled map for dreamview frontend display.
133 const hdmap::HDMap *SimMap() const;
134 bool MapReady() const;
135
136 double x_offset_ = 0.0;
137 double y_offset_ = 0.0;
138
139 // RW lock to protect map data
140 mutable boost::shared_mutex mutex_;
141};
142
143} // namespace dreamview
144} // namespace apollo
bool CheckRoutingPoint(const double x, const double y) const
bool CheckRoutingPointWithHeading(const double x, const double y, const double heading) const
bool PointIsValid(const double x, const double y) const
double GetLaneHeading(const std::string &id_str, double s)
void CollectMapElementIds(const apollo::common::PointENU &point, double raidus, MapElementIds *ids) const
hdmap::Map RetrieveMapElements(const MapElementIds &ids) const
bool ReloadMap(bool force_reload)
bool GetStartPoint(apollo::common::PointENU *start_point) const
bool ConstructLaneWayPointWithLaneId(const double x, const double y, const std::string id, routing::LaneWaypoint *laneWayPoint) const
bool ConstructLaneWayPointWithHeading(const double x, const double y, const double heading, routing::LaneWaypoint *laneWayPoint) const
bool CheckRoutingPointLaneType(apollo::hdmap::LaneInfoConstPtr lane) const
bool GetPoseWithRegardToLane(const double x, const double y, double *theta, double *s) const
size_t CalculateMapHash(const MapElementIds &ids) const
bool GetPathsFromRouting(const apollo::routing::RoutingResponse &routing, std::vector< apollo::hdmap::Path > *paths) const
bool ConstructLaneWayPoint(const double x, const double y, routing::LaneWaypoint *laneWayPoint) const
The function fills out proper routing lane waypoint from the given (x,y) position.
std::string GetParkingSpaceId(const double x, const double y) const
High-precision map loader interface.
Definition hdmap.h:54
std::shared_ptr< const LaneInfo > LaneInfoConstPtr
class register implement
Definition arena_queue.h:37