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.hpp
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 */
16
17#pragma once
18
19#include <rclcpp/rclcpp.hpp>
20#include <functional>
21#include <carma_planning_msgs/msg/trajectory_plan.hpp>
22#include <carma_planning_msgs/msg/guidance_state.hpp>
23#include <gtest/gtest_prod.h>
24
25#include <carma_ros2_utils/carma_lifecycle_node.hpp>
27
28namespace trajectory_executor
29{
30
38 class TrajectoryExecutor : public carma_ros2_utils::CarmaLifecycleNode
39 {
40
41 private:
42 // Subscribers
43 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::TrajectoryPlan> plan_sub_; // Inbound trajectory plan subscriber
44 carma_ros2_utils::SubPtr<carma_planning_msgs::msg::GuidanceState> state_sub_; // Guidance State subscriber
45
46 std::map<std::string, carma_ros2_utils::PubPtr<carma_planning_msgs::msg::TrajectoryPlan>> traj_publisher_map_; // Outbound trajectory plan publishers
47
48 // Timers
49 rclcpp::TimerBase::SharedPtr timer_; // Timer for publishing outbound trajectories to the control plugins
50
51 // Node configuration
53
54 // Trajectory plan tracking data
55 std::unique_ptr<carma_planning_msgs::msg::TrajectoryPlan> cur_traj_;
57
58 protected:
65 std::map<std::string, std::string> queryControlPlugins();
66
73 void onNewTrajectoryPlan(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg);
74
78 void guidanceStateMonitor(carma_planning_msgs::msg::GuidanceState::UniquePtr msg);
79
87 void onTrajEmitTick();
88
89 public:
90
94 explicit TrajectoryExecutor(const rclcpp::NodeOptions &);
95
99 rcl_interfaces::msg::SetParametersResult
100 parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters);
101
103 // Overrides
105 carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &);
106 carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &);
107 };
108
109} // trajectory_executor
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.