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.
approaching_emergency_vehicle_plugin_config.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022-2023 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 double passing_threshold = 15.0; // (Seconds) If the estimated duration until an ERV passes the ego vehicle is below this, the
31 // ERV is considered to be actively passing the ego vehicle.
32
33 double approaching_threshold = 60.0; // (Seconds) If the estimated duration until an ERV passes the ego vehicle is below this, the
34 // ERV is considered to be approaching the ego vehicle.
35
36 double finished_passing_threshold = 152.4; // (Meters) A threshold; an actively-passing ERV is considered to have completed passing the ego vehicle when
37 // its distance in front of the ego vehicle reaches this value.
38
39 double min_lane_following_duration_before_lane_change = 3.0; // (Seconds) The minimum duration of lane following that must be planned before a lane change when in the
40 // MOVING_OVER_FOR_APPROACHING_ERV state.
41
42 double bsm_processing_frequency = 1.0; // (Hz) The rate that incoming BSMs from a specific ERV will be processed by this plugin.
43
44 double speed_limit_reduction_during_passing = 4.4704; // (m/s) The amount that the speed limit of a lanelet will be reduced by when planning a maneuver when an
45 // ERV is actively passing the ego vehicle.
46
47 double minimum_reduced_speed_limit = 2.2352; // (m/s) The minimum speed limit that a lanelet's speed limit will be reduced to when an ERV is actively passing
48 // the ego vehicle.
49
50 double default_speed_limit = 2.2352; // (m/s) The default speed limit used when a lanelet does not have a specified speed limit in the map.
51
52 double reduced_speed_buffer = 1.1176; // (m/s) A buffer value; if the ego vehicle speed is within this speed of its target speed when slowing down for an actively passing
53 // ERV, then this plugin will state in its approaching ERV status message that the ego vehicle has finished slowing down.
54
55 double timeout_check_frequency = 2.0; // (Hz) The frequency at which this plugin will check whether a timeout has occurred for the
56 // currently-tracked ERV.
57
58 double timeout_duration = 5.0; // (Seconds) If no BSM has been received from the currently-tracked ERV, than the ERV will no longer be tracked by
59 // this plugin.
60
61 double minimal_plan_duration = 15.0; // (Seconds) The minimal duration of a generated maneuver plan.
62
63 double buffer_distance_before_stopping = 45.0; // (Meters) The distance that the beginning of a stop_and_wait maneuver can be extended by.
64
65 double stopping_accel_limit_multiplier = 0.5; // (m/s^2) Multiplier for the acceleration limit which will be used for formulating the stopping maneuver
66 // NOTE: This multiplier should be lower than the value used by the plugin that will be used to bring the vehicle to a stop to provide buffer in planning
67
68 double vehicle_acceleration_limit = 2.0; // (m/s^2) The vehicle acceleration limit configured for the CARMA System
69
70 double route_end_point_buffer = 10.0; // (Meters) The distance from the route end point in which the trajectory planner will attempt to stop the ego vehicle for a stop and wait maneuver.
71
72 double approaching_erv_status_publication_frequency = 1.0; // (Hz) The frequency at which this plugin will publish status updates to the Web UI that describe the estimated time until an approaching ERV
73 // passes the ego vehicle, and a description of the ego vehicle's path plan in response to the approaching ERV.
74
75 double warning_broadcast_frequency = 1.0; // (Hz) The frequency at which this plugin will broadcast EmergencyVehicleResponse warning messages to the currently-tracked ERV
76 // when the ego vehicle is in the approaching ERV's path but is unable to change lanes.
77
78 int max_warning_broadcasts = 5; // The maximum number of times that an EmergencyVehicleResponse warning message will be broadcasted to an ERV if an
79 // EmergencyVehicleAck message is not received from the ERV.
80
81 double vehicle_length = 4.0; // (Meters) The length of the host vehicle from its front bumper to its rear bumper.
82
83 std::string lane_following_plugin = "inlanecruising_plugin"; // (No Units) The tactical plugin being used for lane following.
84
85 std::string lane_change_plugin = "cooperative_lanechange"; // (No Units) The tactical plugin being used for lane changes.
86
87 std::string stop_and_wait_plugin = "stop_and_wait_plugin"; // (No Units) The tactical plugin being used for stop and wait maneuvers.
88
89 std::string vehicle_id = "DEFAULT_VEHICLE_ID"; // The ego vehicle's static ID, which is its license plate
90
91 // Stream operator for this config
92 friend std::ostream &operator<<(std::ostream &output, const Config &c)
93 {
94 output << "approaching_emergency_vehicle_plugin::Config { " << std::endl
95 << "passing_threshold: " << c.passing_threshold << std::endl
96 // << "do_not_move_over_threshold: " << c.do_not_move_over_threshold << std::endl
97 << "approaching_threshold: " << c.approaching_threshold << std::endl
98 << "finished_passing_threshold: " << c.finished_passing_threshold << std::endl
99 << "min_lane_following_duration_before_lane_change: " << c.min_lane_following_duration_before_lane_change << std::endl
100 << "bsm_processing_frequency: " << c.bsm_processing_frequency << std::endl
101 << "speed_limit_reduction_during_passing: " << c.speed_limit_reduction_during_passing << std::endl
102 << "minimum_reduced_speed_limit: " << c.minimum_reduced_speed_limit << std::endl
103 << "default_speed_limit: " << c.default_speed_limit << std::endl
104 << "reduced_speed_buffer: " << c.reduced_speed_buffer << std::endl
105 << "timeout_check_frequency: " << c.timeout_check_frequency << std::endl
106 << "timeout_duration: " << c.timeout_duration << std::endl
107 << "minimal_plan_duration: " << c.minimal_plan_duration << std::endl
108 << "buffer_distance_before_stopping: " << c.buffer_distance_before_stopping << std::endl
109 << "stopping_accel_limit_multiplier: " << c.stopping_accel_limit_multiplier << std::endl
110 << "vehicle_acceleration_limit: " << c.vehicle_acceleration_limit << std::endl
111 << "route_end_point_buffer: " << c.route_end_point_buffer << std::endl
112 << "approaching_erv_status_publication_frequency: " << c.approaching_erv_status_publication_frequency << std::endl
113 << "warning_broadcast_frequency: " << c.warning_broadcast_frequency << std::endl
114 << "max_warning_broadcasts: " << c.max_warning_broadcasts << std::endl
115 << "lane_following_plugin: " << c.lane_following_plugin << std::endl
116 << "lane_change_plugin: " << c.lane_change_plugin << std::endl
117 << "stop_and_wait_plugin: " << c.stop_and_wait_plugin << std::endl
118 << "vehicle_id: " << c.vehicle_id << std::endl
119 << "}" << std::endl;
120 return output;
121 }
122 };
123
124} // approaching_emergency_vehicle_plugin
Stuct containing the algorithm configuration values for approaching_emergency_vehicle_plugin.
friend std::ostream & operator<<(std::ostream &output, const Config &c)