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.
template_control_plugin_node.cpp
Go to the documentation of this file.
1/*
2 * Copyright (C) <SUB><year> 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#include "<SUB><package_name>/<SUB><package_name>_node.hpp"
17
18namespace <SUB><package_name>
19{
20 namespace std_ph = std::placeholders;
21
22 Node::Node(const rclcpp::NodeOptions &options)
23 : carma_guidance_plugins::ControlPlugin(options)
24 {
25 // Create initial config
26 config_ = Config();
27
28 // Declare parameters
29 config_.example_param = declare_parameter<std::string>("example_param", config_.example_param);
30 }
31
32 rcl_interfaces::msg::SetParametersResult Node::parameter_update_callback(const std::vector<rclcpp::Parameter> &parameters)
33 {
34 // TODO for the USER: Ensure all parameters can be updated dynamically by adding them to this method
35 auto error = update_params<std::string>({{"example_param", config_.example_param}}, parameters);
36
37 rcl_interfaces::msg::SetParametersResult result;
38
39 result.successful = !error;
40
41 return result;
42 }
43
44 carma_ros2_utils::CallbackReturn Node::on_configure_plugin()
45 {
46 // Reset config
47 config_ = Config();
48
49 // Load parameters
50 get_parameter<std::string>("example_param", config_.example_param);
51
52 // Register runtime parameter update callback
53 add_on_set_parameters_callback(std::bind(&Node::parameter_update_callback, this, std_ph::_1));
54
55 // Setup subscribers
56 example_sub_ = create_subscription<std_msgs::msg::String>("example_input_topic", 10,
57 std::bind(&Node::example_callback, this, std_ph::_1));
58
59 // Setup publishers
60 example_pub_ = create_publisher<std_msgs::msg::String>("example_output_topic", 10);
61
62 // Setup service clients
63 example_client_ = create_client<std_srvs::srv::Empty>("example_used_service");
64
65 // Setup service servers
66 example_service_ = create_service<std_srvs::srv::Empty>("example_provided_service",
67 std::bind(&Node::example_service_callback, this, std_ph::_1, std_ph::_2, std_ph::_3));
68
69 // Setup timers
70 // NOTE: You will not be able to actually publish until in the ACTIVE state
71 // so it may often make more sense for timers to be created in handle_on_activate
72 example_timer_ = create_timer(
73 get_clock(),
74 std::chrono::milliseconds(1000),
75 std::bind(&Node::example_timer_callback, this));
76
77 // Return success if everthing initialized successfully
78 return CallbackReturn::SUCCESS;
79 }
80
81 // Parameter names not shown to prevent unused compile warning. The user may add them back
82 void Node::example_service_callback(const std::shared_ptr<rmw_request_id_t>,
83 const std::shared_ptr<std_srvs::srv::Empty::Request>,
84 std::shared_ptr<std_srvs::srv::Empty::Response>)
85 {
86 RCLCPP_INFO( get_logger(), "Example service callback");
87 }
88
89 void Node::example_timer_callback()
90 {
91 RCLCPP_DEBUG(get_logger(), "Example timer callback");
92 std_msgs::msg::String msg;
93 msg.data = "Hello World!";
94 example_pub_->publish(msg);
95 }
96
97 void Node::example_callback(std_msgs::msg::String::UniquePtr msg)
98 {
99 RCLCPP_INFO_STREAM( get_logger(), "example_sub_ callback called with value: " << msg->data);
100 }
101
102 autoware_msgs::msg::ControlCommandStamped Node::generate_command()
103 {
104 autoware_msgs::msg::ControlCommandStamped msg;
105 // TODO for user: Implement logic to generate control commands here
106 return msg;
107 }
108
109 bool Node::get_availability() {
110 return true; // TODO for user implement actual check on availability if applicable to plugin
111 }
112
113 std::string Node::get_version_id() {
114 return "TODO for user specify plugin version id here";
115 }
116
117} // <SUB><package_name>
118
119#include "rclcpp_components/register_node_macro.hpp"
120
121// Register the component with class_loader
122RCLCPP_COMPONENTS_REGISTER_NODE(<SUB><package_name>::Node)
bool callback(cav_srvs::PlanTrajectory::Request &req, cav_srvs::PlanTrajectory::Response &res)
Definition: helper.cpp:21