19#include <rclcpp/rclcpp.hpp>
21#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <carma_planning_msgs/msg/guidance_state.hpp>
23#include <gtest/gtest_prod.h>
25#include <carma_ros2_utils/carma_lifecycle_node.hpp>
43 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan>
plan_sub_;
44 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState>
state_sub_;
46 std::map<std::string, carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan>>
traj_publisher_map_;
55 std::unique_ptr<carma_planning_msgs::msg::TrajectoryPlan>
cur_traj_;
99 rcl_interfaces::msg::SetParametersResult
rcl_interfaces::msg::SetParametersResult parameter_update_callback(const std::vector< rclcpp::Parameter > ¶meters)
Example callback for dynamic parameter updates.
int timesteps_since_last_traj_
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.
rclcpp::TimerBase::SharedPtr timer_
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.