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.
yield_config.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2020 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
25{
26 double acceleration_adjustment_factor = 4.0; // Adjustment factor for safe and comfortable acceleration/deceleration
27 double on_route_vehicle_collision_horizon_in_s = 10.0; // time horizon for collision detection in s
28 double obstacle_zero_speed_threshold_in_ms = 0.25; // Minimum speed threshold for moving obstacle in m/s to be considered stopped
29 double min_obj_avoidance_plan_time_in_s = 2.0; // minimum object avoidance planning time in s
30 double yield_max_deceleration_in_ms2 = 3.0; // max deceleration value in m/s^2
31 double minimum_safety_gap_in_meters = 2.0; // minimum safety gap in m
32 double vehicle_length = 5.0; // Host vehicle length in m
33 double vehicle_height = 3.0; // Host vehicle height in m
34 double vehicle_width = 2.5; // Host vehicle width in m
35 double max_stop_speed_in_ms = 1.0; // Maximum speed value to consider the ego vehicle stopped in m/s
36 bool enable_cooperative_behavior = true; //parameter to enable cooperative behavior
37 bool always_accept_mobility_request = true; //parameter to always accept mobility request
38 std::string vehicle_id = "DEFAULT_VEHICLE_ID"; // Vehicle id is the license plate of the vehicle
39 int acceptable_passed_timesteps = 10; // acceptable number of timesteps to use the latest known mobility request before switching to yield
40 double intervehicle_collision_distance_in_m = 10.0; //Intervehicle distance that is considered a collision
41 int consecutive_clearance_count_for_obstacles_threshold = 5; //Number of consecutive times the vehicle detects that the obstacle is behind to confirm the obstacle is actually behind
42 double safety_collision_time_gap_in_s = 2.0; // Time gap to finish planning a yield earlier than collision time
43 bool enable_adjustable_gap = true; // Flag to enable yield plugin to check for adjustable gap for example digital gap from map
44 int acceptable_urgency = 5; //Minimum urgency value to consider the mobility request
45 double speed_moving_average_window_size = 3.0; //Window size for speed moving average filter
46 double collision_check_radius_in_m = 150.0; //Radius to check for potential collision
47
48 friend std::ostream& operator<<(std::ostream& output, const YieldPluginConfig& c)
49 {
50 output << "YieldPluginConfig { " << std::endl
51 << "acceleration_adjustment_factor: " << c.acceleration_adjustment_factor << std::endl
52 << "on_route_vehicle_collision_horizon_in_s: " << c.on_route_vehicle_collision_horizon_in_s << std::endl
53 << "obstacle_zero_speed_threshold_in_ms: " << c.obstacle_zero_speed_threshold_in_ms << std::endl
54 << "yield_max_deceleration_in_ms2: " << c.yield_max_deceleration_in_ms2 << std::endl
55 << "minimum_safety_gap_in_meters: " << c.minimum_safety_gap_in_meters << std::endl
56 << "vehicle_length: " << c.vehicle_length << std::endl
57 << "vehicle_height: " << c.vehicle_height << std::endl
58 << "vehicle_width: " << c.vehicle_width << std::endl
59 << "max_stop_speed_in_ms: " << c.max_stop_speed_in_ms << std::endl
60 << "enable_cooperative_behavior: " << c.enable_cooperative_behavior << std::endl
61 << "always_accept_mobility_request: " << c.always_accept_mobility_request << std::endl
62 << "vehicle_id: " << c.vehicle_id << std::endl
63 << "acceptable_passed_timesteps: " << c.acceptable_passed_timesteps << std::endl
64 << "intervehicle_collision_distance_in_m: " << c.intervehicle_collision_distance_in_m << std::endl
65 << "consecutive_clearance_count_for_obstacles_threshold: " << c.consecutive_clearance_count_for_obstacles_threshold << std::endl
66 << "safety_collision_time_gap_in_s: " << c.safety_collision_time_gap_in_s << std::endl
67 << "enable_adjustable_gap: " << c.enable_adjustable_gap << std::endl
68 << "acceptable_urgency: " << c.acceptable_urgency << std::endl
69 << "speed_moving_average_window_size: " << c.speed_moving_average_window_size << std::endl
70 << "collision_check_radius_in_m: " << c.collision_check_radius_in_m << std::endl
71 << "}" << std::endl;
72 return output;
73 }
74};
Stuct containing the algorithm configuration values for the YieldPluginConfig.
bool always_accept_mobility_request
friend std::ostream & operator<<(std::ostream &output, const YieldPluginConfig &c)
double max_stop_speed_in_ms
double collision_check_radius_in_m
std::string vehicle_id
double speed_moving_average_window_size
double acceleration_adjustment_factor
int consecutive_clearance_count_for_obstacles_threshold
double yield_max_deceleration_in_ms2
double intervehicle_collision_distance_in_m
double obstacle_zero_speed_threshold_in_ms
double on_route_vehicle_collision_horizon_in_s
bool enable_cooperative_behavior
double min_obj_avoidance_plan_time_in_s
double minimum_safety_gap_in_meters
double safety_collision_time_gap_in_s