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::TrajectoryExecutor Class Reference

#include <trajectory_executor_node.hpp>

Inheritance diagram for trajectory_executor::TrajectoryExecutor:
Inheritance graph
Collaboration diagram for trajectory_executor::TrajectoryExecutor:
Collaboration graph

Public Member Functions

 TrajectoryExecutor (const rclcpp::NodeOptions &)
 Constructor for TrajectoryExecutor. More...
 
rcl_interfaces::msg::SetParametersResult parameter_update_callback (const std::vector< rclcpp::Parameter > &parameters)
 Example callback for dynamic parameter updates. More...
 
carma_ros2_utils::CallbackReturn handle_on_configure (const rclcpp_lifecycle::State &)
 
carma_ros2_utils::CallbackReturn handle_on_activate (const rclcpp_lifecycle::State &)
 

Protected Member Functions

std::map< std::string, std::string > queryControlPlugins ()
 Helper function to query control plugin registration system. More...
 
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. More...
 
void guidanceStateMonitor (carma_planning_msgs::msg::GuidanceState::UniquePtr msg)
 Monitor the guidance state and set the current trajector as null_ptr. More...
 
void onTrajEmitTick ()
 Timer callback to be invoked at our output tickrate. Outputs current trajectory plan to the first control plugin in it's point list. If this is our second or later timestep on the same trajectory, consumes the first point in the point list before transmission. More...
 

Private Attributes

carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > plan_sub_
 
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::GuidanceState > state_sub_
 
std::map< std::string, carma_ros2_utils::PubPtr< carma_planning_msgs::msg::TrajectoryPlan > > traj_publisher_map_
 
rclcpp::TimerBase::SharedPtr timer_
 
Config config_
 
std::unique_ptr< carma_planning_msgs::msg::TrajectoryPlan > cur_traj_
 
int timesteps_since_last_traj_ {0}
 

Detailed Description

Trajectory Executor package primary worker class

Handles subscribing to inbound plans from Plan Delegator component. control plugin registration querying, and then coordination of execution of that plan amongst multiple control plugins.

Definition at line 38 of file trajectory_executor_node.hpp.

Constructor & Destructor Documentation

◆ TrajectoryExecutor()

trajectory_executor::TrajectoryExecutor::TrajectoryExecutor ( const rclcpp::NodeOptions &  options)
explicit

Constructor for TrajectoryExecutor.

Definition at line 22 of file trajectory_executor_node.cpp.

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 }

References config_, trajectory_executor::Config::default_control_plugin, trajectory_executor::Config::default_control_plugin_topic, and trajectory_executor::Config::trajectory_publish_rate.

Member Function Documentation

◆ guidanceStateMonitor()

void trajectory_executor::TrajectoryExecutor::guidanceStateMonitor ( carma_planning_msgs::msg::GuidanceState::UniquePtr  msg)
protected

Monitor the guidance state and set the current trajector as null_ptr.

Definition at line 165 of file trajectory_executor_node.cpp.

166 {
167 // TODO need to handle control handover once alernative planner system is finished
169 {
170 cur_traj_= nullptr;
171 }
172 }
std::unique_ptr< carma_planning_msgs::msg::TrajectoryPlan > cur_traj_

References cur_traj_, and lightbar_manager::ENGAGED.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ handle_on_activate()

carma_ros2_utils::CallbackReturn trajectory_executor::TrajectoryExecutor::handle_on_activate ( const rclcpp_lifecycle::State &  )

Definition at line 108 of file trajectory_executor_node.cpp.

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 }
void onTrajEmitTick()
Timer callback to be invoked at our output tickrate. Outputs current trajectory plan to the first con...

References config_, onTrajEmitTick(), timer_, and trajectory_executor::Config::trajectory_publish_rate.

Here is the call graph for this function:

◆ handle_on_configure()

carma_ros2_utils::CallbackReturn trajectory_executor::TrajectoryExecutor::handle_on_configure ( const rclcpp_lifecycle::State &  )

Definition at line 65 of file trajectory_executor_node.cpp.

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 }
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > &parameters)
Example callback for dynamic parameter updates.
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::map< std::string, carma_ros2_utils::PubPtr< carma_planning_msgs::msg::TrajectoryPlan > > traj_publisher_map_

References config_, cur_traj_, trajectory_executor::Config::default_control_plugin, trajectory_executor::Config::default_control_plugin_topic, guidanceStateMonitor(), onNewTrajectoryPlan(), parameter_update_callback(), plan_sub_, queryControlPlugins(), state_sub_, traj_publisher_map_, and trajectory_executor::Config::trajectory_publish_rate.

Here is the call graph for this function:

◆ onNewTrajectoryPlan()

void trajectory_executor::TrajectoryExecutor::onNewTrajectoryPlan ( carma_planning_msgs::msg::TrajectoryPlan::UniquePtr  msg)
protected

Callback to be invoked when a new trajectory plan is received on our inbound plan topic.

Parameters
msgThe new TrajectoryPlan message

Definition at line 154 of file trajectory_executor_node.cpp.

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 }

References cur_traj_, and timesteps_since_last_traj_.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ onTrajEmitTick()

void trajectory_executor::TrajectoryExecutor::onTrajEmitTick ( )
protected

Timer callback to be invoked at our output tickrate. Outputs current trajectory plan to the first control plugin in it's point list. If this is our second or later timestep on the same trajectory, consumes the first point in the point list before transmission.

Definition at line 121 of file trajectory_executor_node.cpp.

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 }

References config_, cur_traj_, trajectory_executor::Config::default_control_plugin, timesteps_since_last_traj_, and traj_publisher_map_.

Referenced by handle_on_activate().

Here is the caller graph for this function:

◆ parameter_update_callback()

rcl_interfaces::msg::SetParametersResult trajectory_executor::TrajectoryExecutor::parameter_update_callback ( const std::vector< rclcpp::Parameter > &  parameters)

Example callback for dynamic parameter updates.

Definition at line 34 of file trajectory_executor_node.cpp.

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 }

References config_, trajectory_executor::Config::default_control_plugin, trajectory_executor::Config::default_control_plugin_topic, and trajectory_executor::Config::trajectory_publish_rate.

Referenced by handle_on_configure().

Here is the caller graph for this function:

◆ queryControlPlugins()

std::map< std::string, std::string > trajectory_executor::TrajectoryExecutor::queryControlPlugins ( )
protected

Helper function to query control plugin registration system.

Returns
A map of control plugin name -> control plugin input topics for all discovered control plugins

Definition at line 48 of file trajectory_executor_node.cpp.

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 }

References config_, trajectory_executor::Config::default_control_plugin, and trajectory_executor::Config::default_control_plugin_topic.

Referenced by handle_on_configure().

Here is the caller graph for this function:

Member Data Documentation

◆ config_

Config trajectory_executor::TrajectoryExecutor::config_
private

◆ cur_traj_

std::unique_ptr<carma_planning_msgs::msg::TrajectoryPlan> trajectory_executor::TrajectoryExecutor::cur_traj_
private

◆ plan_sub_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan> trajectory_executor::TrajectoryExecutor::plan_sub_
private

Definition at line 43 of file trajectory_executor_node.hpp.

Referenced by handle_on_configure().

◆ state_sub_

carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> trajectory_executor::TrajectoryExecutor::state_sub_
private

Definition at line 44 of file trajectory_executor_node.hpp.

Referenced by handle_on_configure().

◆ timer_

rclcpp::TimerBase::SharedPtr trajectory_executor::TrajectoryExecutor::timer_
private

Definition at line 49 of file trajectory_executor_node.hpp.

Referenced by handle_on_activate().

◆ timesteps_since_last_traj_

int trajectory_executor::TrajectoryExecutor::timesteps_since_last_traj_ {0}
private

Definition at line 56 of file trajectory_executor_node.hpp.

Referenced by onNewTrajectoryPlan(), and onTrajEmitTick().

◆ traj_publisher_map_

std::map<std::string, carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan> > trajectory_executor::TrajectoryExecutor::traj_publisher_map_
private

Definition at line 46 of file trajectory_executor_node.hpp.

Referenced by handle_on_configure(), and onTrajEmitTick().


The documentation for this class was generated from the following files: