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.
pure_pursuit_wrapper_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
21namespace pure_pursuit_wrapper {
26{
27 double vehicle_response_lag = 0.2; // An approximation of the delay (sec) between sent vehicle commands and the vehicle begining a meaningful acceleration to that command
32 bool is_delay_compensation = true; // not to be confused with vehicle_response_lag, which is applied nonetheless
36
37 // integrator part
38 double dt = 0.1;
39 double integrator_max_pp = 0.0;
40 double integrator_min_pp = 0.0;
41 double Ki_pp = 0.0;
43
44 friend std::ostream& operator<<(std::ostream& output, const PurePursuitWrapperConfig& c)
45 {
46 output << "PurePursuitWrapperConfig { " << std::endl
47 << "vehicle_response_lag: " << c.vehicle_response_lag << std::endl
48 << "minimum_lookahead_distance: " << c.minimum_lookahead_distance << std::endl
49 << "maximum_lookahead_distance: " << c.maximum_lookahead_distance << std::endl
50 << "speed_to_lookahead_ratio: " << c.speed_to_lookahead_ratio << std::endl
51 << "is_interpolate_lookahead_point: " << c.is_interpolate_lookahead_point << std::endl
52 << "is_delay_compensation: " << c.is_delay_compensation << std::endl
53 << "emergency_stop_distance: " << c.emergency_stop_distance << std::endl
54 << "speed_thres_traveling_direction: " << c.speed_thres_traveling_direction << std::endl
55 << "dist_front_rear_wheels: " << c.dist_front_rear_wheels << std::endl
56 // integrator part:
57 << "dt: " << c.dt << std::endl
58 << "integrator_max_pp: " << c.integrator_max_pp << std::endl
59 << "integrator_min_pp: " << c.integrator_min_pp << std::endl
60 << "Ki_pp: " << c.Ki_pp << std::endl
61 << "is_integrator_enabled: " << c.is_integrator_enabled << std::endl
62 << "}" << std::endl;
63 return output;
64 }
65};
66}
Struct containing the algorithm configuration values for the PurePursuitWrapperConfig.
friend std::ostream & operator<<(std::ostream &output, const PurePursuitWrapperConfig &c)