Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
TrackPos.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <lanelet2_core/primitives/Lanelet.h>
20#include <lanelet2_core/primitives/Point.h>
21
22namespace carma_wm
23{
35{
36public:
37 double downtrack = 0;
38 double crosstrack = 0;
39
45 TrackPos(double down_track, double cross_track) : downtrack(down_track), crosstrack(cross_track)
46 {
47 }
54 TrackPos(const lanelet::ArcCoordinates& arc_coord) : downtrack(arc_coord.length), crosstrack(-arc_coord.distance)
55 {
56 }
57
63 inline lanelet::ArcCoordinates toArcCoordinates()
64 {
65 return lanelet::ArcCoordinates{ downtrack, -crosstrack };
66 }
67
68 // Overload == and != operators
69 bool operator==(const TrackPos& other) const
70 {
71 return this == &other || (this->downtrack == other.downtrack && this->crosstrack == other.crosstrack);
72 }
73
74 bool operator!=(const TrackPos& other) const
75 {
76 return !(*this == other);
77 }
78};
79} //namespace carma_wm
Position in a track based coordinate system where the axis are downtrack and crosstrack....
Definition: TrackPos.hpp:35
bool operator!=(const TrackPos &other) const
Definition: TrackPos.hpp:74
lanelet::ArcCoordinates toArcCoordinates()
Returns a lanelet ArcCoordinate built from this TrackPos where downtrack = ArcCoordinates....
Definition: TrackPos.hpp:63
bool operator==(const TrackPos &other) const
Definition: TrackPos.hpp:69
TrackPos(const lanelet::ArcCoordinates &arc_coord)
Constructor from lanelet ArcCoordinates which are converted to TrackPos where downtrack = ArcCoordina...
Definition: TrackPos.hpp:54
TrackPos(double down_track, double cross_track)
Constructor.
Definition: TrackPos.hpp:45