|
| 1 | +// Copyright 2024 The Autoware Contributors |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#include "heartbeat.hpp" |
| 16 | + |
| 17 | +#include <utility> |
| 18 | + |
| 19 | +namespace default_ad_api |
| 20 | +{ |
| 21 | + |
| 22 | +HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartbeat", options) |
| 23 | +{ |
| 24 | + // Move this function so that the timer no longer holds it as a reference. |
| 25 | + const auto on_timer = [this]() { |
| 26 | + autoware_ad_api::system::Heartbeat::Message heartbeat; |
| 27 | + heartbeat.stamp = now(); |
| 28 | + heartbeat.seq = ++sequence_; // Wraps at 65535. |
| 29 | + pub_->publish(heartbeat); |
| 30 | + }; |
| 31 | + |
| 32 | + const auto adaptor = component_interface_utils::NodeAdaptor(this); |
| 33 | + adaptor.init_pub(pub_); |
| 34 | + |
| 35 | + const auto period = rclcpp::Rate(10.0).period(); |
| 36 | + timer_ = rclcpp::create_timer(this, get_clock(), period, std::move(on_timer)); |
| 37 | +} |
| 38 | + |
| 39 | +} // namespace default_ad_api |
| 40 | + |
| 41 | +#include <rclcpp_components/register_node_macro.hpp> |
| 42 | +RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::HeartbeatNode) |
0 commit comments