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.
config.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 <iostream>
20#include <vector>
21
23{
24
28 struct Config
29 {
30
32 float32_t min_x = -1000;
33
35 float32_t max_x = 1000;
36
38 float32_t min_y = -1000;
39
41 float32_t max_y = 1000;
42
44 size_t cell_side_length = 100;
45
46 // Stream operator for this config
47 friend std::ostream &operator<<(std::ostream &output, const Config &c)
48 {
49 output << "approximate_intersection::Config { " << std::endl
50 << "min_x: " << c.min_x << std::endl
51 << "max_x: " << c.max_x << std::endl
52 << "min_y: " << c.min_y << std::endl
53 << "max_y: " << c.max_y << std::endl
54 << "cell_side_length: " << c.cell_side_length << std::endl
55 << "}" << std::endl;
56 return output;
57 }
58 };
59
60} // approximate_intersection
Stuct containing the algorithm configuration values for approximate_intersection.
Definition: config.hpp:29
float32_t min_y
Maximum y dimension.
Definition: config.hpp:38
float32_t max_x
Maximum x dimension.
Definition: config.hpp:35
friend std::ostream & operator<<(std::ostream &output, const Config &c)
Definition: config.hpp:47
float32_t max_y
Maximum y dimension.
Definition: config.hpp:41
float32_t min_x
Maximum x dimension.
Definition: config.hpp:32
size_t cell_side_length
Cell size length.
Definition: config.hpp:44