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.
trajectory_executor_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
18namespace trajectory_executor
19{
20 namespace std_ph = std::placeholders;
21
22 TrajectoryExecutor::TrajectoryExecutor(const rclcpp::NodeOptions &options)
23 : carma_ros2_utils::CarmaLifecycleNode(options)
24 {
25 // Create initial config
26 config_ = Config();
27
28 // Declare parameters
29 config_.trajectory_publish_rate = declare_parameter<double>("trajectory_publish_rate", config_.trajectory_publish_rate);
30 config_.default_control_plugin = declare_parameter<std::string>("default_control_plugin", config_.default_control_plugin);
31 config_.default_control_plugin_topic = declare_parameter<std::string>("default_control_plugin_topic", config_.default_control_plugin_topic);
32 }
33
34 rcl_interfaces::msg::SetParametersResult TrajectoryExecutor::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
35 {
36 auto error = update_params<double>({{"trajectory_publish_rate", config_.trajectory_publish_rate}}, parameters);
37 auto error_2 = update_params<std::string>({
38 {"default_control_plugin", config_.default_control_plugin},
39 {"default_control_plugin_topic", config_.default_control_plugin_topic}}, parameters);
40
41 rcl_interfaces::msg::SetParametersResult result;
42
43 result.successful = !error && !error_2;
44
45 return result;
46 }
47
48 std::map<std::string, std::string> TrajectoryExecutor::queryControlPlugins()
49 {
50 // Hard coded stub for MVP since plugin manager won't be developed yet
51 // TODO: Query plugin manager to receive actual list of plugins and their corresponding topics
52 RCLCPP_DEBUG_STREAM(get_logger(), "Executing stub behavior for plugin discovery MVP...");
53 std::map<std::string, std::string> out;
54
56
57 //Hardcoding platoon control plugins
58 std::string control_plugin2 = "platooning_control";
59 std::string control_plugin_topic2 = "/guidance/plugins/platooning_control/plan_trajectory";
60 out[control_plugin2] = control_plugin_topic2;
61
62 return out;
63 }
64
65 carma_ros2_utils::CallbackReturn TrajectoryExecutor::handle_on_configure(const rclcpp_lifecycle::State &)
66 {
67 RCLCPP_INFO_STREAM(get_logger(), "TrajectoryExecutor trying to configure");
68
69 // Reset config
70 config_ = Config();
71
72 // Load parameters
73 get_parameter<double>("trajectory_publish_rate", config_.trajectory_publish_rate);
74 get_parameter<std::string>("default_control_plugin", config_.default_control_plugin);
75 get_parameter<std::string>("default_control_plugin_topic", config_.default_control_plugin_topic);
76
77 RCLCPP_INFO_STREAM(get_logger(), "Loaded params: " << config_);
78
79 // Register runtime parameter update callback
80 add_on_set_parameters_callback(std::bind(&TrajectoryExecutor::parameter_update_callback, this, std_ph::_1));
81
82 // Setup subscribers
83 plan_sub_ = create_subscription<carma_planning_msgs::msg::TrajectoryPlan>("trajectory", 5,
84 std::bind(&TrajectoryExecutor::onNewTrajectoryPlan, this, std_ph::_1));
85 state_sub_ = create_subscription<carma_planning_msgs::msg::GuidanceState>("state", 5,
86 std::bind(&TrajectoryExecutor::guidanceStateMonitor, this, std_ph::_1));
87
88 cur_traj_ = std::unique_ptr<carma_planning_msgs::msg::TrajectoryPlan>();
89
90 RCLCPP_DEBUG_STREAM(get_logger(), "Setting up publishers for control plugin topics...");
91
92 std::map<std::string, carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan>> control_plugin_topics;
93 auto discovered_control_plugins = queryControlPlugins();
94
95 for (auto it = discovered_control_plugins.begin(); it != discovered_control_plugins.end(); it++)
96 {
97 RCLCPP_DEBUG_STREAM(get_logger(), "Trajectory executor discovered control plugin " << it->first.c_str() << " listening on topic " << it->second.c_str());
98 carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan> control_plugin_pub = create_publisher<carma_planning_msgs::msg::TrajectoryPlan>(it->second, 1000);
99 control_plugin_topics.insert(std::make_pair(it->first, control_plugin_pub));
100 }
101
102 traj_publisher_map_ = control_plugin_topics;
103 RCLCPP_DEBUG_STREAM(get_logger(), "TrajectoryExecutor component initialized succesfully!");
104
105 // Return success if everthing initialized successfully
106 return CallbackReturn::SUCCESS;
107 }
108 carma_ros2_utils::CallbackReturn TrajectoryExecutor::handle_on_activate(const rclcpp_lifecycle::State &)
109 {
110 // Create timer for publishing outbound trajectories to the control plugins
111 int timer_period_ms = (1 / config_.trajectory_publish_rate) * 1000; // Conversion from frequency (Hz) to milliseconds time period
112
113 timer_ = create_timer(
114 get_clock(),
115 std::chrono::milliseconds(timer_period_ms),
116 std::bind(&TrajectoryExecutor::onTrajEmitTick, this));
117
118 return CallbackReturn::SUCCESS;
119 }
120
122 {
123 RCLCPP_DEBUG_STREAM(get_logger(), "TrajectoryExecutor tick start!");
124
125 if (cur_traj_ != nullptr) {
126 // Determine the relevant control plugin for the current timestep
127 std::string control_plugin = cur_traj_->trajectory_points[0].controller_plugin_name;
128 // if it instructed to use default control_plugin
129 if (control_plugin == "default" || control_plugin =="") {
130 control_plugin = config_.default_control_plugin;
131 }
132
133 std::map<std::string, carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan>>::iterator it = traj_publisher_map_.find(control_plugin);
134 if (it != traj_publisher_map_.end()) {
135 RCLCPP_DEBUG_STREAM(get_logger(), "Found match for control plugin " << control_plugin.c_str() << " at point " << timesteps_since_last_traj_ << " in current trajectory!");
136 it->second->publish(*cur_traj_);
137 } else {
138 std::ostringstream description_builder;
139 description_builder << "No match found for control plugin "
140 << control_plugin << " at point "
141 << timesteps_since_last_traj_ << " in current trajectory!";
142
143 throw std::invalid_argument(description_builder.str());
144 }
146 } else {
147 RCLCPP_DEBUG_STREAM(get_logger(), "Awaiting initial trajectory publication...");
148 }
149
150 RCLCPP_DEBUG_STREAM(get_logger(), "TrajectoryExecutor tick completed succesfully!");
151
152 }
153
154 void TrajectoryExecutor::onNewTrajectoryPlan(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
155 {
156 RCLCPP_DEBUG_STREAM(get_logger(), "Received new trajectory plan!");
157 RCLCPP_DEBUG_STREAM(get_logger(), "New Trajectory plan ID: " << msg->trajectory_id);
158 RCLCPP_DEBUG_STREAM(get_logger(), "New plan contains " << msg->trajectory_points.size() << " points");
159
160 cur_traj_ = std::unique_ptr<carma_planning_msgs::msg::TrajectoryPlan>(move(msg));
162 RCLCPP_INFO_STREAM(get_logger(), "Successfully swapped trajectories!");
163 }
164
165 void TrajectoryExecutor::guidanceStateMonitor(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
166 {
167 // TODO need to handle control handover once alernative planner system is finished
169 {
170 cur_traj_= nullptr;
171 }
172 }
173
174} // trajectory_executor
175
176#include "rclcpp_components/register_node_macro.hpp"
177
178// Register the component with class_loader
179RCLCPP_COMPONENTS_REGISTER_NODE(trajectory_executor::TrajectoryExecutor)
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.
TrajectoryExecutor(const rclcpp::NodeOptions &)
Constructor for TrajectoryExecutor.
void onNewTrajectoryPlan(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
Callback to be invoked when a new trajectory plan is received on our inbound plan topic.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > plan_sub_
void guidanceStateMonitor(carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
Monitor the guidance state and set the current trajector as null_ptr.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > state_sub_
std::map< std::string, std::string > queryControlPlugins()
Helper function to query control plugin registration system.
std::unique_ptr< carma_planning_msgs::msg::TrajectoryPlan > cur_traj_
void onTrajEmitTick()
Timer callback to be invoked at our output tickrate. Outputs current trajectory plan to the first con...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &)
std::map< std::string, carma_ros2_utils::PubPtr< carma_planning_msgs::msg::TrajectoryPlan > > traj_publisher_map_
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &)
Struct containing the algorithm configuration values for trajectory_executor.