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.
|
#include <trajectory_executor_node.hpp>
Public Member Functions | |
TrajectoryExecutor (const rclcpp::NodeOptions &) | |
Constructor for TrajectoryExecutor. More... | |
rcl_interfaces::msg::SetParametersResult | parameter_update_callback (const std::vector< rclcpp::Parameter > ¶meters) |
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} |
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.
|
explicit |
Constructor for TrajectoryExecutor.
Definition at line 22 of file trajectory_executor_node.cpp.
References config_, trajectory_executor::Config::default_control_plugin, trajectory_executor::Config::default_control_plugin_topic, and trajectory_executor::Config::trajectory_publish_rate.
|
protected |
Monitor the guidance state and set the current trajector as null_ptr.
Definition at line 165 of file trajectory_executor_node.cpp.
References cur_traj_, and lightbar_manager::ENGAGED.
Referenced by handle_on_configure().
carma_ros2_utils::CallbackReturn trajectory_executor::TrajectoryExecutor::handle_on_activate | ( | const rclcpp_lifecycle::State & | ) |
Definition at line 108 of file trajectory_executor_node.cpp.
References config_, onTrajEmitTick(), timer_, and trajectory_executor::Config::trajectory_publish_rate.
carma_ros2_utils::CallbackReturn trajectory_executor::TrajectoryExecutor::handle_on_configure | ( | const rclcpp_lifecycle::State & | ) |
Definition at line 65 of file trajectory_executor_node.cpp.
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.
|
protected |
Callback to be invoked when a new trajectory plan is received on our inbound plan topic.
msg | The new TrajectoryPlan message |
Definition at line 154 of file trajectory_executor_node.cpp.
References cur_traj_, and timesteps_since_last_traj_.
Referenced by handle_on_configure().
|
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.
References config_, cur_traj_, trajectory_executor::Config::default_control_plugin, timesteps_since_last_traj_, and traj_publisher_map_.
Referenced by handle_on_activate().
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.
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().
|
protected |
Helper function to query control plugin registration system.
Definition at line 48 of file trajectory_executor_node.cpp.
References config_, trajectory_executor::Config::default_control_plugin, and trajectory_executor::Config::default_control_plugin_topic.
Referenced by handle_on_configure().
|
private |
Definition at line 52 of file trajectory_executor_node.hpp.
Referenced by TrajectoryExecutor(), handle_on_activate(), handle_on_configure(), onTrajEmitTick(), parameter_update_callback(), and queryControlPlugins().
|
private |
Definition at line 55 of file trajectory_executor_node.hpp.
Referenced by guidanceStateMonitor(), handle_on_configure(), onNewTrajectoryPlan(), and onTrajEmitTick().
|
private |
Definition at line 43 of file trajectory_executor_node.hpp.
Referenced by handle_on_configure().
|
private |
Definition at line 44 of file trajectory_executor_node.hpp.
Referenced by handle_on_configure().
|
private |
Definition at line 49 of file trajectory_executor_node.hpp.
Referenced by handle_on_activate().
|
private |
Definition at line 56 of file trajectory_executor_node.hpp.
Referenced by onNewTrajectoryPlan(), and onTrajEmitTick().
|
private |
Definition at line 46 of file trajectory_executor_node.hpp.
Referenced by handle_on_configure(), and onTrajEmitTick().