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.
control_plugin.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 */
16
17#include <functional>
19
20
22{
23 namespace std_ph = std::placeholders;
24
25 ControlPlugin::ControlPlugin(const rclcpp::NodeOptions &options)
26 : PluginBaseNode(options)
27 {}
28
30 {
31 return "control/trajectory_control";
32 }
33
35 {
36 return carma_planning_msgs::msg::Plugin::CONTROL;
37 }
38
39 void ControlPlugin::current_pose_callback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
40 {
41 RCLCPP_DEBUG(rclcpp::get_logger("carma_guidance_plugins"), "Received pose message");
42 current_pose_ = *msg;
43 }
44
45 void ControlPlugin::current_twist_callback(geometry_msgs::msg::TwistStamped::UniquePtr msg)
46 {
47 RCLCPP_DEBUG(rclcpp::get_logger("carma_guidance_plugins"), "Received twist message");
48 current_twist_ = *msg;
49 }
50
51 void ControlPlugin::current_trajectory_callback(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
52 {
53 RCLCPP_DEBUG(rclcpp::get_logger("carma_guidance_plugins"), "Received trajectory message");
55 }
56
57 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_configure(const rclcpp_lifecycle::State &prev_state)
58 {
59 // Initialize subscribers and publishers
60 current_pose_sub_ = create_subscription<geometry_msgs::msg::PoseStamped>("current_pose", 1,
61 std::bind(&ControlPlugin::current_pose_callback, this, std_ph::_1));
62
63 current_velocity_sub_ = create_subscription<geometry_msgs::msg::TwistStamped>("vehicle/twist", 1,
64 std::bind(&ControlPlugin::current_twist_callback, this, std_ph::_1));
65
66 trajectory_plan_sub_ = create_subscription<carma_planning_msgs::msg::TrajectoryPlan>(std::string(get_name()) + "/plan_trajectory", 1,
67 std::bind(&ControlPlugin::current_trajectory_callback, this, std_ph::_1));
68
69 vehicle_cmd_pub_ = create_publisher<autoware_msgs::msg::ControlCommandStamped>("ctrl_raw", 1);
70
71 command_timer_ = create_timer(
72 get_clock(),
73 std::chrono::milliseconds(33), // Spin at 30 Hz per plugin API
74 [this]() {
75 if (this->get_activation_status()) // Only trigger when activated
76 {
77 this->vehicle_cmd_pub_->publish(this->generate_command());
78
79 }
80 });
81
82 return PluginBaseNode::handle_on_configure(prev_state);
83 }
84
85 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_activate(const rclcpp_lifecycle::State &prev_state)
86 {
87 return PluginBaseNode::handle_on_activate(prev_state);
88 }
89
90 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_deactivate(const rclcpp_lifecycle::State &prev_state)
91 {
92 return PluginBaseNode::handle_on_deactivate(prev_state);
93 }
94
95 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_cleanup(const rclcpp_lifecycle::State &prev_state)
96 {
97 return PluginBaseNode::handle_on_cleanup(prev_state);
98 }
99
100 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_shutdown(const rclcpp_lifecycle::State &prev_state)
101 {
102 return PluginBaseNode::handle_on_shutdown(prev_state);
103 }
104
105 carma_ros2_utils::CallbackReturn ControlPlugin::handle_on_error(const rclcpp_lifecycle::State &prev_state, const std::string &exception_string)
106 {
107 return PluginBaseNode::handle_on_error(prev_state, exception_string);
108 }
109
110} // carma_guidance_plugins
rclcpp::TimerBase::SharedPtr command_timer_
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override final
std::string get_capability() override
Get the capability string representing this plugins capabilities Method must be overriden by extendin...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override final
void current_pose_callback(geometry_msgs::msg::PoseStamped::UniquePtr msg)
boost::optional< geometry_msgs::msg::TwistStamped > current_twist_
The most recent velocity message received by this node.
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override final
virtual void current_trajectory_callback(carma_planning_msgs::msg::TrajectoryPlan::UniquePtr msg)
Extending class provided method which can optionally handle trajectory plan callbacks.
uint8_t get_type() override final
Returns the type of this plugin according to the carma_planning_msgs::Plugin type enum....
carma_ros2_utils::SubPtr< geometry_msgs::msg::PoseStamped > current_pose_sub_
boost::optional< carma_planning_msgs::msg::TrajectoryPlan > current_trajectory_
The most recent trajectory received by this plugin.
carma_ros2_utils::SubPtr< carma_planning_msgs::msg::TrajectoryPlan > trajectory_plan_sub_
carma_ros2_utils::PubPtr< autoware_msgs::msg::ControlCommandStamped > vehicle_cmd_pub_
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override final
virtual autoware_msgs::msg::ControlCommandStamped generate_command()=0
Extending class provided method which should generate a command message which will be published to th...
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override final
ControlPlugin(const rclcpp::NodeOptions &)
ControlPlugin constructor.
void current_twist_callback(geometry_msgs::msg::TwistStamped::UniquePtr msg)
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override final
carma_ros2_utils::SubPtr< geometry_msgs::msg::TwistStamped > current_velocity_sub_
boost::optional< geometry_msgs::msg::PoseStamped > current_pose_
The most recent pose message received by this node.
PluginBaseNode provides default functionality for all carma guidance plugins. This includes basic sta...
virtual bool get_activation_status() final
Returns the activation status of this plugin. The plugins API callbacks will only be triggered when t...
carma_ros2_utils::CallbackReturn handle_on_deactivate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_error(const rclcpp_lifecycle::State &, const std::string &exception_string) override
carma_ros2_utils::CallbackReturn handle_on_cleanup(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_configure(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_activate(const rclcpp_lifecycle::State &) override
carma_ros2_utils::CallbackReturn handle_on_shutdown(const rclcpp_lifecycle::State &) override