Skip to content

Commit

Permalink
feat(default_ad_api): add heratbeat api (autowarefoundation#6969)
Browse files Browse the repository at this point in the history
* feat(default_ad_api): add heratbeat api

Signed-off-by: Takagi, Isamu <[email protected]>

* fix node dying

Signed-off-by: Takagi, Isamu <[email protected]>

---------

Signed-off-by: Takagi, Isamu <[email protected]>
  • Loading branch information
isamu-takagi authored May 24, 2024
1 parent d827b1b commit 7b51a43
Show file tree
Hide file tree
Showing 5 changed files with 121 additions and 0 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,36 @@
// Copyright 2024 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef AUTOWARE_AD_API_SPECS__SYSTEM_HPP_
#define AUTOWARE_AD_API_SPECS__SYSTEM_HPP_

#include <rclcpp/qos.hpp>

#include <autoware_adapi_v1_msgs/msg/heartbeat.hpp>

namespace autoware_ad_api::system
{

struct Heartbeat
{
using Message = autoware_adapi_v1_msgs::msg::Heartbeat;
static constexpr char name[] = "/api/system/heartbeat";
static constexpr size_t depth = 10;
static constexpr auto reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
static constexpr auto durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
};

} // namespace autoware_ad_api::system

#endif // AUTOWARE_AD_API_SPECS__SYSTEM_HPP_
2 changes: 2 additions & 0 deletions system/default_ad_api/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ autoware_package()

ament_auto_add_library(${PROJECT_NAME} SHARED
src/fail_safe.cpp
src/heartbeat.cpp
src/interface.cpp
src/localization.cpp
src/motion.cpp
Expand All @@ -23,6 +24,7 @@ ament_auto_add_library(${PROJECT_NAME} SHARED
rclcpp_components_register_nodes(${PROJECT_NAME}
"default_ad_api::AutowareStateNode"
"default_ad_api::FailSafeNode"
"default_ad_api::HeartbeatNode"
"default_ad_api::InterfaceNode"
"default_ad_api::LocalizationNode"
"default_ad_api::MotionNode"
Expand Down
1 change: 1 addition & 0 deletions system/default_ad_api/launch/default_ad_api.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ def generate_launch_description():
components = [
create_api_node("autoware_state", "AutowareStateNode"),
create_api_node("fail_safe", "FailSafeNode"),
create_api_node("heartbeat", "HeartbeatNode"),
create_api_node("interface", "InterfaceNode"),
create_api_node("localization", "LocalizationNode"),
create_api_node("motion", "MotionNode"),
Expand Down
42 changes: 42 additions & 0 deletions system/default_ad_api/src/heartbeat.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright 2024 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "heartbeat.hpp"

#include <utility>

namespace default_ad_api
{

HeartbeatNode::HeartbeatNode(const rclcpp::NodeOptions & options) : Node("heartbeat", options)
{
// Move this function so that the timer no longer holds it as a reference.
const auto on_timer = [this]() {
autoware_ad_api::system::Heartbeat::Message heartbeat;
heartbeat.stamp = now();
heartbeat.seq = ++sequence_; // Wraps at 65535.
pub_->publish(heartbeat);
};

const auto adaptor = component_interface_utils::NodeAdaptor(this);
adaptor.init_pub(pub_);

const auto period = rclcpp::Rate(10.0).period();
timer_ = rclcpp::create_timer(this, get_clock(), period, std::move(on_timer));
}

} // namespace default_ad_api

#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(default_ad_api::HeartbeatNode)
40 changes: 40 additions & 0 deletions system/default_ad_api/src/heartbeat.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
// Copyright 2024 The Autoware Contributors
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef HEARTBEAT_HPP_
#define HEARTBEAT_HPP_

#include <autoware_ad_api_specs/system.hpp>
#include <rclcpp/rclcpp.hpp>

// This file should be included after messages.
#include "utils/types.hpp"

namespace default_ad_api
{

class HeartbeatNode : public rclcpp::Node
{
public:
explicit HeartbeatNode(const rclcpp::NodeOptions & options);

private:
rclcpp::TimerBase::SharedPtr timer_;
Pub<autoware_ad_api::system::Heartbeat> pub_;
uint16_t sequence_ = 0;
};

} // namespace default_ad_api

#endif // HEARTBEAT_HPP_

0 comments on commit 7b51a43

Please sign in to comment.