Skip to content

Commit

Permalink
feat: add autoware_control_center and autoware_node
Browse files Browse the repository at this point in the history
Signed-off-by: M. Fatih Cırıt <[email protected]>
  • Loading branch information
xmfcx committed Nov 27, 2024
1 parent 3eee8f6 commit 6d85528
Show file tree
Hide file tree
Showing 46 changed files with 2,456 additions and 0 deletions.
52 changes: 52 additions & 0 deletions common/autoware_control_center/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
cmake_minimum_required(VERSION 3.8)
project(autoware_control_center)

find_package(autoware_cmake REQUIRED)
autoware_package()

ament_auto_add_library(${PROJECT_NAME} SHARED
src/control_center_node.cpp
include/autoware/control_center/control_center_node.hpp
)

# In order to instantiate only a single instance, we have to use custom main function
#rclcpp_components_register_node(${PROJECT_NAME}
# PLUGIN "autoware::control_center::ControlCenter"
# EXECUTABLE ${PROJECT_NAME}_node
#)

ament_auto_add_executable(${PROJECT_NAME}_node
src/control_center_main.cpp
)

if(BUILD_TESTING)
add_smoke_test(${PROJECT_NAME} ${PROJECT_NAME}_node
TEST_PARAM_FILENAMES "config/control_center.param.yaml"
)

install(DIRECTORY
test/config/
DESTINATION share/${PROJECT_NAME}/test/config/
)

file(GLOB_RECURSE TEST_FILES test/*.cpp)

foreach(TEST_FILE ${TEST_FILES})
# Get the test name without directory and extension
get_filename_component(TEST_NAME ${TEST_FILE} NAME_WE)

# Add each test separately
ament_add_ros_isolated_gtest(${TEST_NAME} ${TEST_FILE} TIMEOUT 10)
target_include_directories(${TEST_NAME} PRIVATE src/include)
target_link_libraries(${TEST_NAME} ${PROJECT_NAME})
ament_target_dependencies(${TEST_NAME}
rclcpp
rclcpp_lifecycle
autoware_utils
autoware_control_center_msgs)
endforeach()
endif()

ament_auto_package(INSTALL_TO_SHARE
launch
config)
100 changes: 100 additions & 0 deletions common/autoware_control_center/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,100 @@
# Autoware Control Center

## Abbreviations

- **ACC:** Autoware Control Center
- **AN:** Autoware Node
- **HB:** Heartbeat

## Overview

The Autoware Control Center (ACC) is a core package within the Autoware system, designed to manage and monitor Autoware
nodes (ANs).

It provides services for the registration, de-registration, and error handling of ANs, as well as publishing reports on
their status.

ACC maintains an internal registry to keep track of registered ANs.

## Interfaces

### Services

#### Register

Registers an Autoware node to the ACC.

- **Topic:** `/autoware/control_center/srv/register`
- **Type:** `autoware_control_center_msgs::srv::Register`

#### Deregister

De-registers an Autoware node from the ACC.

- **Topic:** `/autoware/control_center/srv/deregister`
- **Type:** `autoware_control_center_msgs::srv::Deregister`

### Subscribers

#### Heartbeat (**Source:** Autoware Node)

Subscribes to the heartbeat topic of an Autoware node after its registration.
ACC controls the liveness of Autoware nodes by monitoring this topic.

This topic also contains the information about the node's status.

- **Topic:** `/autoware_node_name/heartbeat`
- **Type:** `autoware_control_center_msgs::msg::Heartbeat`
- **Source:** An Autoware Node

### Publishers

#### NodeReports

Publishes reports on the current status of registered Autoware nodes.

- **Topic:** `/autoware/control_center/node_reports`
- **Type:** `autoware_control_center_msgs::msg::NodeReports`

## Parameters

| Name | Type | Default Value | Description |
| --------------------- | -------- | ------------- | ------------------------------------------------------------------------ |
| `deadline_ms` | `double` | `220.0` | Maximum duration to wait for a heartbeat before considering a node dead. |
| `report_publish_rate` | `double` | `1.0` | Frequency (in Hz) at which NodeReports are published. |

## Singleton Constraint

To ensure that only one instance of the ACC is running at any given time, two checks are performed in the main function:

### 1. Lockfile Check

This lockfile mechanism is fast and reliable for single-machine scenarios.
It prevents multiple instances of ACC from running concurrently on the same machine.

**Path:** `/tmp/autoware_control_center_node.lock`

### 2. Network-Wide Node Name Check

This involves gathering all node names and comparing them with the ACC node name (`/autoware/control_center`).
While this method is slower and less reliable than the lockfile check,
it is necessary for scenarios where the ACC is run across a network of machines.
This ensures that no other instance of ACC is running on any other machine within the network.

## Usage

`ros2 launch autoware_control_center control_center.launch.xml`

## Workflow

When an Autoware Node starts, it registers itself with the ACC.

The ACC then subscribes to the heartbeat topic of the Autoware node to monitor its liveliness.

If the ACC does not receive a heartbeat from the Autoware node within the specified deadline,
it considers the node to be dead.

## Credits

- Heartbeat functionality is based on ROS 2 [software_watchdogs](https://github.com/ros-safety/software_watchdogs)
package.
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
/**:
ros__parameters:
deadline_ms: 220.0
report_publish_rate: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
// 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__CONTROL_CENTER__CONTROL_CENTER_NODE_HPP_
#define AUTOWARE__CONTROL_CENTER__CONTROL_CENTER_NODE_HPP_

#include <rclcpp_lifecycle/lifecycle_node.hpp>

#include <autoware_control_center_msgs/msg/heartbeat.hpp>
#include <autoware_control_center_msgs/msg/node_report.hpp>
#include <autoware_control_center_msgs/msg/node_reports.hpp>
#include <autoware_control_center_msgs/msg/node_status_activity.hpp>
#include <autoware_control_center_msgs/msg/node_status_operational.hpp>
#include <autoware_control_center_msgs/srv/deregister.hpp>
#include <autoware_control_center_msgs/srv/register.hpp>
#include <unique_identifier_msgs/msg/uuid.hpp>

#include <map>
#include <memory>
#include <string>
#include <tuple>
#include <unordered_map>
#include <vector>

namespace autoware::control_center
{

class ControlCenter : public rclcpp_lifecycle::LifecycleNode
{
public:
using SharedPtr = std::shared_ptr<ControlCenter>;
using NodeReport = autoware_control_center_msgs::msg::NodeReport;
explicit ControlCenter(const rclcpp::NodeOptions & options);

struct NodeInfo
{
using SharedPtr = std::shared_ptr<NodeInfo>;
using ConstSharedPtr = std::shared_ptr<const NodeInfo>;

NodeReport report;
rclcpp::Subscription<autoware_control_center_msgs::msg::Heartbeat>::SharedPtr heartbeat_sub;
};

private:
using Heartbeat = autoware_control_center_msgs::msg::Heartbeat;
using NodeReports = autoware_control_center_msgs::msg::NodeReports;
using NodeStatusActivity = autoware_control_center_msgs::msg::NodeStatusActivity;
using NodeStatusOperational = autoware_control_center_msgs::msg::NodeStatusOperational;
using ResultDeregistration = autoware_control_center_msgs::msg::ResultDeregistration;
using ResultRegistration = autoware_control_center_msgs::msg::ResultRegistration;
using Deregister = autoware_control_center_msgs::srv::Deregister;
using Register = autoware_control_center_msgs::srv::Register;

std::tuple<ResultRegistration, std::optional<unique_identifier_msgs::msg::UUID>> register_node(
const std::string & node_name);
ControlCenter::ResultDeregistration deregister_node(
const unique_identifier_msgs::msg::UUID & uuid);

bool is_registered(const unique_identifier_msgs::msg::UUID & uuid) const;
bool is_registered(const std::string & name) const;

/// @brief Retrieves the UUID of a registered node.
/// @note Ensure the node is registered using `is_registered(node_name)` before calling this
/// function.
unique_identifier_msgs::msg::UUID get_uuid(const std::string & node_name) const;

/// @brief Retrieves the NodeInfo of a registered node.
/// @note Ensure the node is registered using `is_registered(uuid)` before calling this function.
ControlCenter::NodeInfo::ConstSharedPtr get_node_info(
const unique_identifier_msgs::msg::UUID & uuid) const;

void on_heartbeat(
const autoware_control_center_msgs::msg::Heartbeat::SharedPtr heartbeat,
const unique_identifier_msgs::msg::UUID & uuid);

void on_deadline_missed(
rclcpp::QOSDeadlineRequestedInfo & event, const unique_identifier_msgs::msg::UUID & uuid);

void on_liveliness_changed(
rclcpp::QOSLivelinessChangedInfo & event, const unique_identifier_msgs::msg::UUID & uuid);

void publish_node_reports();

void on_register_node(
const std::shared_ptr<Register::Request> request, std::shared_ptr<Register::Response> response);

void on_deregister_node(
const std::shared_ptr<Deregister::Request> request,
std::shared_ptr<Deregister::Response> response);

rclcpp::Service<Register>::SharedPtr srv_register_;
rclcpp::Service<Deregister>::SharedPtr srv_deregister_;
rclcpp::Publisher<NodeReports>::SharedPtr pub_reports_;
rclcpp::TimerBase::SharedPtr timer_publish_reports_;

std::map<std::string, unique_identifier_msgs::msg::UUID> node_name_to_uuid_;
std::map<std::array<uint8_t, 16>, NodeInfo::SharedPtr> uuid_to_info_;

double deadline_ms_;
double report_publish_rate_;
};

} // namespace autoware::control_center

#endif // AUTOWARE__CONTROL_CENTER__CONTROL_CENTER_NODE_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="param_path" default="$(find-pkg-share autoware_control_center)/config/control_center.param.yaml"/>

<node pkg="autoware_control_center" exec="autoware_control_center_node" name="control_center" output="screen">
<param from="$(var param_path)"/>
</node>
</launch>
34 changes: 34 additions & 0 deletions common/autoware_control_center/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>autoware_control_center</name>
<version>0.0.0</version>
<description>
Autoware Control Center (ACC) is an Autoware.Core package designed to manage
and monitor Autoware nodes within a system.
</description>
<maintainer email="[email protected]">M. Fatih Cırıt</maintainer>
<license>Apache-2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_control_center_msgs</depend>
<depend>autoware_utils</depend>
<depend>lifecycle_msgs</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>rclcpp_lifecycle</depend>

<test_depend>ament_cmake_gtest</test_depend>
<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>autoware_lint_common</test_depend>
<test_depend>autoware_testing</test_depend>
<test_depend>autoware_utils</test_depend>
<test_depend>ros_testing</test_depend>

<export>
<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit 6d85528

Please sign in to comment.