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.
platooning_tactical_plugin_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) 2022 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
17#include <carma_ros2_utils/timers/ROSTimerFactory.hpp>
18
20{
21 namespace std_ph = std::placeholders;
22
23 Node::Node(const rclcpp::NodeOptions &options)
24 : carma_guidance_plugins::TacticalPlugin(options)
25 {
26 // Create initial config
28
29 // Declare parameters
30 config_.trajectory_time_length = declare_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
31 config_.curve_resample_step_size = declare_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
32 config_.default_downsample_ratio = declare_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
33 config_.turn_downsample_ratio = declare_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
34 config_.minimum_speed = declare_parameter<double>("minimum_speed", config_.minimum_speed);
35 config_.max_accel_multiplier = declare_parameter<double>("max_accel_multiplier", config_.max_accel_multiplier);
36 config_.lat_accel_multiplier = declare_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
37 config_.back_distance = declare_parameter<double>("back_distance", config_.back_distance);
38 config_.speed_moving_average_window_size = declare_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
39 config_.curvature_moving_average_window_size = declare_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
40 config_.max_accel = declare_parameter<double>("vehicle_acceleration_limit", config_.max_accel);
41 config_.lateral_accel_limit = declare_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
42 config_.enable_object_avoidance = declare_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
43 config_.buffer_ending_downtrack = declare_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
44
47
48 RCLCPP_INFO_STREAM(get_logger(), "PlatooningTacticalPlugin Params" << config_);
49
50 }
51
52 rcl_interfaces::msg::SetParametersResult Node::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
53 {
54 auto error = update_params<bool>({
55 {"enable_object_avoidance", config_.enable_object_avoidance}
56 }, parameters);
57
58 auto error2 = update_params<int>({
59 {"default_downsample_ratio", config_.default_downsample_ratio},
60 {"turn_downsample_ratio", config_.turn_downsample_ratio},
61 {"speed_moving_average_window_size", config_.speed_moving_average_window_size},
62 {"curvature_moving_average_window_size", config_.curvature_moving_average_window_size}
63 }, parameters);
64
65 auto error3 = update_params<double>({
66 {"trajectory_time_length", config_.trajectory_time_length},
67 {"curve_resample_step_size", config_.curve_resample_step_size},
68 {"minimum_speed", config_.minimum_speed},
69 {"max_accel_multiplier", config_.max_accel_multiplier},
70 {"lat_accel_multiplier", config_.lat_accel_multiplier},
71 {"back_distance", config_.back_distance},
72 {"buffer_ending_downtrack", config_.buffer_ending_downtrack}
73 }, parameters); // Accel limits system wide and not allowed to be updated per node
74
77
78 rcl_interfaces::msg::SetParametersResult result;
79
80 result.successful = !error && !error2 && !error3;
81
82 if (result.successful && worker_)
83 {
84 worker_->set_config(config_);
85 }
86
87 return result;
88 }
89
90 carma_ros2_utils::CallbackReturn Node::on_configure_plugin()
91 {
92 // Reset config
94
95 // Load parameters
96 get_parameter<double>("trajectory_time_length", config_.trajectory_time_length);
97 get_parameter<double>("curve_resample_step_size", config_.curve_resample_step_size);
98 get_parameter<int>("default_downsample_ratio", config_.default_downsample_ratio);
99 get_parameter<int>("turn_downsample_ratio", config_.turn_downsample_ratio);
100 get_parameter<double>("minimum_speed", config_.minimum_speed);
101 get_parameter<double>("max_accel_multiplier", config_.max_accel_multiplier);
102 get_parameter<double>("lat_accel_multiplier", config_.lat_accel_multiplier);
103 get_parameter<double>("back_distance", config_.back_distance);
104 get_parameter<int>("speed_moving_average_window_size", config_.speed_moving_average_window_size);
105 get_parameter<int>("curvature_moving_average_window_size", config_.curvature_moving_average_window_size);
106 get_parameter<double>("vehicle_acceleration_limit", config_.max_accel);
107 get_parameter<double>("vehicle_lateral_accel_limit", config_.lateral_accel_limit);
108 get_parameter<bool>("enable_object_avoidance", config_.enable_object_avoidance);
109 get_parameter<double>("buffer_ending_downtrack", config_.buffer_ending_downtrack);
110
113
114 RCLCPP_INFO_STREAM(get_logger(), "PlatooningTacticalPlugin Params" << config_);
115
116 // Register runtime parameter update callback
117 add_on_set_parameters_callback(std::bind(&Node::parameter_update_callback, this, std_ph::_1));
118
119 worker_ = std::make_shared<PlatooningTacticalPlugin>(get_world_model(), config_,
120 std::make_shared<carma_ros2_utils::timers::ROSTimerFactory>(shared_from_this()));
121
122 // Return success if everything initialized successfully
123 return CallbackReturn::SUCCESS;
124 }
125
127 std::shared_ptr<rmw_request_id_t>,
128 carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req,
129 carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp)
130 {
131 if (!worker_)
132 return;
133
134 worker_->plan_trajectory_cb(*req, *resp);
135 }
136
138 return true;
139 }
140
141 std::string Node::get_version_id() {
142 return "v4.0";
143 }
144
145} // platooning_tactical_plugin
146
147#include "rclcpp_components/register_node_macro.hpp"
148
149// Register the component with class_loader
150RCLCPP_COMPONENTS_REGISTER_NODE(platooning_tactical_plugin::Node)
virtual carma_wm::WorldModelConstPtr get_world_model() final
Method to return the default world model provided as a convience by this base class If this method or...
ROS node for the PlatooningTacticalPlugin to initialize and configure parameters and publishers/subsc...
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.
std::shared_ptr< PlatooningTacticalPlugin > worker_
std::string get_version_id() override
Returns the version id of this plugin.
carma_ros2_utils::CallbackReturn on_configure_plugin()
This method should be used to load parameters and will be called on the configure state transition.
Node(const rclcpp::NodeOptions &)
Node constructor.
bool get_availability() override
Get the availability status of this plugin based on the current operating environment....
void plan_trajectory_callback(std::shared_ptr< rmw_request_id_t >, carma_planning_msgs::srv::PlanTrajectory::Request::SharedPtr req, carma_planning_msgs::srv::PlanTrajectory::Response::SharedPtr resp) override
Extending class provided callback which should return a planned trajectory based on the provided traj...
Stuct containing the algorithm configuration values for the PlatooningTacticalPlugin.