Apollo  6.0
Open source self driving car software
route_segments.h
Go to the documentation of this file.
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 <limits>
24 #include <string>
25 #include <vector>
26 
27 #include "gflags/gflags.h"
28 
29 #include "modules/common/proto/pnc_point.pb.h"
30 #include "modules/common/vehicle_state/proto/vehicle_state.pb.h"
31 #include "modules/routing/proto/routing.pb.h"
32 
35 
36 namespace apollo {
37 namespace hdmap {
38 
50 class RouteSegments : public std::vector<LaneSegment> {
51  public:
55  RouteSegments() = default;
56 
67  routing::ChangeLaneType NextAction() const;
68  void SetNextAction(routing::ChangeLaneType action);
69 
80  routing::ChangeLaneType PreviousAction() const;
81  void SetPreviousAction(routing::ChangeLaneType action);
82 
87  bool CanExit() const;
88  void SetCanExit(bool can_exit);
89 
99  bool GetProjection(const common::PointENU &point_enu,
100  common::SLPoint *sl_point, LaneWaypoint *waypoint) const;
101  bool GetProjection(const common::math::Vec2d &point,
102  common::SLPoint *sl_point, LaneWaypoint *waypoint) const;
103 
104  bool GetWaypoint(const double s, LaneWaypoint *waypoint) const;
105 
113  bool CanDriveFrom(const LaneWaypoint &waypoint) const;
114 
115  /*
116  * This is the point that is the end of the original passage in routing.
117  * It is used to check if the vehicle is out of current routing.
118  * The LaneWaypoint.lane is nullptr if the end of the passage is not on the
119  * RouteSegment.
120  */
121  const LaneWaypoint &RouteEndWaypoint() const;
122  void SetRouteEndWaypoint(const LaneWaypoint &waypoint);
123 
141  bool Stitch(const RouteSegments &other);
142 
143  bool Shrink(const common::math::Vec2d &point, const double look_backward,
144  const double look_forward);
145 
146  bool Shrink(const double s, const double look_backward,
147  const double look_forward);
148 
149  bool Shrink(const double s, const LaneWaypoint &waypoint,
150  const double look_backward, const double look_forward);
151 
152  bool IsOnSegment() const;
153  void SetIsOnSegment(bool on_segment);
154 
155  bool IsNeighborSegment() const;
156  void SetIsNeighborSegment(bool is_neighbor);
157 
158  void SetId(const std::string &id);
159  const std::string &Id() const;
160 
164  LaneWaypoint FirstWaypoint() const;
165 
169  LaneWaypoint LastWaypoint() const;
170 
174  bool IsWaypointOnSegment(const LaneWaypoint &waypoint) const;
175 
181  bool IsConnectedSegment(const RouteSegments &other) const;
182 
183  bool StopForDestination() const;
184  void SetStopForDestination(bool stop_for_destination);
185 
189  void SetProperties(const RouteSegments &other);
190 
191  static bool WithinLaneSegment(const LaneSegment &lane_segment,
192  const LaneWaypoint &waypoint);
193 
194  static bool WithinLaneSegment(const LaneSegment &lane_segment,
195  const routing::LaneWaypoint &waypoint);
196 
197  static bool WithinLaneSegment(const routing::LaneSegment &lane_segment,
198  const LaneWaypoint &waypoint);
199 
200  static bool WithinLaneSegment(const routing::LaneSegment &lane_segment,
201  const routing::LaneWaypoint &waypoint);
202 
203  static double Length(const RouteSegments &segments);
204 
205  private:
206  LaneWaypoint route_end_waypoint_;
207 
211  bool can_exit_ = false;
212 
216  bool is_on_segment_ = false;
217 
222  bool is_neighbor_ = false;
223 
224  routing::ChangeLaneType next_action_ = routing::FORWARD;
225 
226  routing::ChangeLaneType previous_action_ = routing::FORWARD;
227 
228  std::string id_;
229 
235  bool stop_for_destination_ = false;
236 };
237 
238 } // namespace hdmap
239 } // namespace apollo
bool IsWaypointOnSegment(const LaneWaypoint &waypoint) const
Check if a waypoint is on segment.
routing::ChangeLaneType NextAction() const
class RouteSegments
Definition: route_segments.h:50
void SetId(const std::string &id)
bool IsConnectedSegment(const RouteSegments &other) const
Check if we can reach the other segment from current segment just by following lane.
bool CanDriveFrom(const LaneWaypoint &waypoint) const
Check whether the map allows a vehicle can reach current RouteSegment from a point on a lane (LaneWay...
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool Stitch(const RouteSegments &other)
const LaneWaypoint & RouteEndWaypoint() const
static bool WithinLaneSegment(const LaneSegment &lane_segment, const LaneWaypoint &waypoint)
void SetCanExit(bool can_exit)
const std::string & Id() const
bool GetWaypoint(const double s, LaneWaypoint *waypoint) const
Definition: path.h:74
routing::ChangeLaneType PreviousAction() const
void SetIsNeighborSegment(bool is_neighbor)
void SetRouteEndWaypoint(const LaneWaypoint &waypoint)
void SetNextAction(routing::ChangeLaneType action)
void SetProperties(const RouteSegments &other)
Copy the properties of other segments to current one.
Implements a class of 2-dimensional vectors.
Definition: vec2d.h:42
void SetPreviousAction(routing::ChangeLaneType action)
void SetStopForDestination(bool stop_for_destination)
LaneWaypoint FirstWaypoint() const
bool Shrink(const common::math::Vec2d &point, const double look_backward, const double look_forward)
LaneWaypoint LastWaypoint() const
bool GetProjection(const common::PointENU &point_enu, common::SLPoint *sl_point, LaneWaypoint *waypoint) const
void SetIsOnSegment(bool on_segment)
static double Length(const RouteSegments &segments)
Definition: path.h:39