{"id":13762068,"url":"https://github.com/uleroboticsgroup/yasmin","last_synced_at":"2026-04-02T02:59:20.927Z","repository":{"id":81000308,"uuid":"491060086","full_name":"uleroboticsgroup/yasmin","owner":"uleroboticsgroup","description":"YASMIN (Yet Another State MachINe)","archived":false,"fork":false,"pushed_at":"2025-04-23T21:35:12.000Z","size":39189,"stargazers_count":168,"open_issues_count":1,"forks_count":34,"subscribers_count":7,"default_branch":"main","last_synced_at":"2025-04-23T22:26:01.184Z","etag":null,"topics":["cpp","python","ros2","ros2-foxy","ros2-humble","ros2-jazzy","state-machine"],"latest_commit_sha":null,"homepage":"","language":"C++","has_issues":true,"has_wiki":null,"has_pages":null,"mirror_url":null,"source_name":null,"license":"gpl-3.0","status":null,"scm":"git","pull_requests_enabled":true,"icon_url":"https://github.com/uleroboticsgroup.png","metadata":{"files":{"readme":"README.md","changelog":null,"contributing":null,"funding":null,"license":"LICENSE","code_of_conduct":null,"threat_model":null,"audit":null,"citation":null,"codeowners":null,"security":null,"support":null,"governance":null,"roadmap":null,"authors":null,"dei":null,"publiccode":null,"codemeta":null,"zenodo":null}},"created_at":"2022-05-11T10:21:48.000Z","updated_at":"2025-04-23T21:35:15.000Z","dependencies_parsed_at":null,"dependency_job_id":"d8e3374b-3b7c-4134-8f6a-bc2d8ea7f3c9","html_url":"https://github.com/uleroboticsgroup/yasmin","commit_stats":null,"previous_names":[],"tags_count":18,"template":false,"template_full_name":null,"repository_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repositories/uleroboticsgroup%2Fyasmin","tags_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repositories/uleroboticsgroup%2Fyasmin/tags","releases_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repositories/uleroboticsgroup%2Fyasmin/releases","manifests_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repositories/uleroboticsgroup%2Fyasmin/manifests","owner_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/owners/uleroboticsgroup","download_url":"https://codeload.github.com/uleroboticsgroup/yasmin/tar.gz/refs/heads/main","host":{"name":"GitHub","url":"https://github.com","kind":"github","repositories_count":253428283,"owners_count":21906887,"icon_url":"https://github.com/github.png","version":null,"created_at":"2022-05-30T11:31:42.601Z","updated_at":"2022-07-04T15:15:14.044Z","host_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub","repositories_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repositories","repository_names_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/repository_names","owners_url":"https://repos.ecosyste.ms/api/v1/hosts/GitHub/owners"}},"keywords":["cpp","python","ros2","ros2-foxy","ros2-humble","ros2-jazzy","state-machine"],"created_at":"2024-08-03T14:00:34.461Z","updated_at":"2026-04-02T02:59:20.896Z","avatar_url":"https://github.com/uleroboticsgroup.png","language":"C++","readme":"# YASMIN (Yet Another State MachINe)\n\n\u003cp align=\"center\"\u003e\n  \u003cimg src=\"./docs/logo.png\" width=\"50%\" /\u003e\n\u003c/p\u003e\n\n**YASMIN** is a project focused on implementing robot behaviors using Finite State Machines (FSM). It is available for ROS 2, Python and C++.\n\n\u003cdiv align=\"center\"\u003e\n\n[![License: GPL-v3.0](https://img.shields.io/badge/GitHub-GPL--3.0-informational)](https://opensource.org/license/gpl-3-0)\n[![GitHub release](https://img.shields.io/github/release/uleroboticsgroup/yasmin.svg)](https://github.com/uleroboticsgroup/yasmin/releases)\n[![Code Size](https://img.shields.io/github/languages/code-size/uleroboticsgroup/yasmin.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin?branch=main)\n[![Dependencies](https://img.shields.io/librariesio/github/uleroboticsgroup/yasmin?branch=main)](https://libraries.io/github/uleroboticsgroup/yasmin?branch=main)\n[![Last Commit](https://img.shields.io/github/last-commit/uleroboticsgroup/yasmin.svg)](https://github.com/uleroboticsgroup/yasmin/commits/main)\n\n[![GitHub issues](https://img.shields.io/github/issues/uleroboticsgroup/yasmin)](https://github.com/uleroboticsgroup/yasmin/issues)\n[![GitHub pull requests](https://img.shields.io/github/issues-pr/uleroboticsgroup/yasmin)](https://github.com/uleroboticsgroup/yasmin/pulls)\n[![Contributors](https://img.shields.io/github/contributors/uleroboticsgroup/yasmin.svg)](https://github.com/uleroboticsgroup/yasmin/graphs/contributors)\n\n[![Python Formatter Check](https://github.com/uleroboticsgroup/yasmin/actions/workflows/python-formatter.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/python-formatter.yml?branch=main)\n[![C++ Formatter Check](https://github.com/uleroboticsgroup/yasmin/actions/workflows/cpp-formatter.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/cpp-formatter.yml?branch=main) [![Documentation Deployment](https://github.com/uleroboticsgroup/yasmin/actions/workflows/documentation-deployment.yml/badge.svg)](https://uleroboticsgroup.github.io/yasmin)\n\n| ROS 2 Distro |                                                                                                            Build and Test                                                                                                            |                                                               Docker Image                                                                |\n| :----------: | :----------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------: | :---------------------------------------------------------------------------------------------------------------------------------------: |\n|   **Foxy**   |        [![Foxy Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/foxy-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/foxy-build-test.yml?branch=main)         |     [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-foxy-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=foxy)     |\n| **Galatic**  |  [![Galactic Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/galactic-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/galactic-build-test.yml?branch=main)   | [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-galactic-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=galactic) |\n|  **Humble**  | [![Humble Build and Test](https://github.com/uleroboticsgroup/yasmin/actions/workflows/humble-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/humble-build-test.yml?branch=main) |   [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-humble-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=humble)   |\n|   **Iron**   |        [![Iron Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/iron-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/iron-build-test.yml?branch=main)         |     [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-iron-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=iron)     |\n|  **Jazzy**   |       [![Jazzy Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/jazzy-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/jazzy-build-test.yml?branch=main)       |    [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-jazzy-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=jazzy)    |\n|  **Kilted**  |     [![Kilted Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/kilted-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/kilted-build-test.yml?branch=main)      |   [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-kilted-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=kilted)   |\n| **Rolling**  |    [![Rolling Build](https://github.com/uleroboticsgroup/yasmin/actions/workflows/rolling-build-test.yml/badge.svg?branch=main)](https://github.com/uleroboticsgroup/yasmin/actions/workflows/rolling-build-test.yml?branch=main)    |  [![Docker Image](https://img.shields.io/badge/Docker%20Image%20-rolling-blue)](https://hub.docker.com/r/mgons/yasmin/tags?name=rolling)  |\n\n\u003c/div\u003e\n\n## Table of Contents\n\n1. [Features](#features)\n2. [Installation](#installation)\n   - [Debian Packages](#debian-packages)\n   - [Building from Source](#building-from-source)\n   - [Docker](#docker)\n3. [Demos](#demos)\n   - [Python](#python)\n   - [Cpp](#cpp)\n4. [Cross-Language ROS Interface Communication](#crosslanguage-ros-interface-communication)\n5. [YASMIN Editor](#yasmin-editor)\n   - [Getting Started](#getting-started)\n6. [YASMIN Viewer](#yasmin-viewer)\n   - [Getting Started](#getting-started-1)\n   - [Custom Host and Port](#custom-host-and-port)\n7. [Citations](#citations)\n\n## Key Features\n\n- **ROS 2 Integration**: Integrates with ROS 2 for easy deployment and interaction.\n- **Support for Python and C++**: Available for both Python and C++, making it flexible for a variety of use cases.\n- **Rapid Prototyping**: Designed for fast prototyping, allowing quick iteration of state machine behaviors.\n- **Predefined States**: Includes states for interacting with ROS 2 action clients, service clients, and topics.\n- **Data Sharing with Blackboards**: Utilizes blackboards for data sharing between states and state machines.\n- **State Management**: Supports cancellation and stopping of state machines, including halting the current executing state.\n- **Web Viewer**: Features an integrated web viewer for real-time monitoring of state machine execution.\n\n## Installation\n\n### Debian Packages\n\nTo install YASMIN and its packages, use the following command:\n\n```shell\nsudo apt install ros-$ROS_DISTRO-yasmin ros-$ROS_DISTRO-yasmin-*\n```\n\n### Building from Source\n\nFollow these steps to build the source code from this repository:\n\n```shell\ncd ~/ros2_ws/src\ngit clone https://github.com/uleroboticsgroup/yasmin.git\ncd ~/ros2_ws\nrosdep install --from-paths src --ignore-src -r -y\ncolcon build\n```\n\nThen, you can run the tests as follow:\n\n```shell\ncolcon test --packages-select yasmin yasmin_ros yasmin_factory\ncolcon test-result --verbose\n```\n\n### Docker\n\nIf your operating system doesn't support ROS 2, docker is a great alternative. You can use an image from [Dockerhub](https://hub.docker.com/r/mgons/yasmin/) or create your own images. First of all, to build the image you have to use the following command:\n\n```shell\n## Assuming you are in the YASMIN project directory\ndocker build -t yasmin .\n```\n\nTo use a shortcut the docker build, you may use the following command:\n\n```shell\n## Assuming you are in the YASMIN project directory\nmake docker_build\n```\n\nAfter the image is created, run a docker container with the following command:\n\n```shell\ndocker run -it --net=host --ipc=host --privileged --env=\"DISPLAY\" --env=\"QT_X11_NO_MITSHM=1\" --volume=\"/tmp/.X11-unix:/tmp/.X11-unix:rw\" --volume=\"${XAUTHORITY}:/root/.Xauthority\" --entrypoint /bin/bash yasmin\n```\n\nTo use a shortcut the docker run, you may use following command:\n\n```shell\n## Assuming you are in the YASMIN project directory\nmake docker_run\n```\n\n## Demos\n\nThere are some examples, for both Python and C++, that can be found in [yasmin_demos](./yasmin_demos/).\n\n\u003cp align=\"center\"\u003e\n  \u003cimg src=\"./docs/demo.gif\" width=\"65%\" /\u003e\n\u003c/p\u003e\n\n### Python\n\n#### Vanilla Demo (FSM)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos yasmin_demo.py\n```\n\n```python\nimport time\nimport rclpy\n\nimport yasmin\nfrom yasmin import State, Blackboard, StateMachine\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_viewer import YasminViewerPub\n\n\n# Define the FooState class, inheriting from the State class\nclass FooState(State):\n    \"\"\"\n    Represents the Foo state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the FooState instance, setting up the outcomes.\n\n        Outcomes:\n            outcome1: Indicates the state should continue to the Bar state.\n            outcome2: Indicates the state should finish execution and return.\n        \"\"\"\n        super().__init__([\"outcome1\", \"outcome2\"])\n        self.counter = 0\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Foo state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which can be \"outcome1\" or \"outcome2\".\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state FOO\")\n        time.sleep(3)  # Simulate work by sleeping\n\n        if self.counter \u003c 3:\n            self.counter += 1\n            blackboard[\"foo_str\"] = f\"Counter: {self.counter}\"\n            return \"outcome1\"\n        else:\n            return \"outcome2\"\n\n\n# Define the BarState class, inheriting from the State class\nclass BarState(State):\n    \"\"\"\n    Represents the Bar state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the BarState instance, setting up the outcome.\n\n        Outcomes:\n            outcome3: Indicates the state should transition back to the Foo state.\n        \"\"\"\n        super().__init__(outcomes=[\"outcome3\"])\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Bar state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which will always be \"outcome3\".\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state BAR\")\n        time.sleep(3)  # Simulate work by sleeping\n\n        yasmin.YASMIN_LOG_INFO(blackboard[\"foo_str\"])\n        return \"outcome3\"\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_demo\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"FOO\",\n        FooState(),\n        transitions={\n            \"outcome1\": \"BAR\",\n            \"outcome2\": \"outcome4\",\n        },\n    )\n    sm.add_state(\n        \"BAR\",\n        BarState(),\n        transitions={\n            \"outcome3\": \"FOO\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Blackboard Remapping Demo\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos remap_demo.py\n```\n\n```python\nimport rclpy\n\nimport yasmin\nfrom yasmin import State, Blackboard, StateMachine\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros.basic_outcomes import SUCCEED\nfrom yasmin_viewer import YasminViewerPub\n\n\nclass Foo(State):\n    \"\"\"\n    Represents the Foo state in the state machine.\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the FooState instance, setting up the outcomes.\n\n        Outcomes:\n            SUCCEED: Indicates the state should continue to the next state.\n        \"\"\"\n        super().__init__(outcomes=[SUCCEED])\n\n    def execute(self, blackboard: Blackboard):\n        \"\"\"\n        Executes the logic for the Foo state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which can be SUCCEED.\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        data = blackboard[\"foo_data\"]\n        yasmin.YASMIN_LOG_INFO(f\"{data}\")\n        blackboard[\"foo_out_data\"] = data\n        return SUCCEED\n\n\nclass BarState(State):\n    \"\"\"\n    Represents the Bar state in the state machine.\n\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the BarState instance, setting up the outcomes.\n\n        Outcomes:\n            SUCCEDED: Indicates the state should continue to the next state.\n        \"\"\"\n        super().__init__(outcomes=[SUCCEED])\n\n    def execute(self, blackboard: Blackboard):\n        \"\"\"\n        Executes the logic for the Bar state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which can be SUCCEED.\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        data = blackboard[\"bar_data\"]\n        yasmin.YASMIN_LOG_INFO(f\"{data}\")\n        return SUCCEED\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_remapping_demo\")\n\n    # Create a blackboard with initial data\n    blackboard = Blackboard()\n    blackboard[\"msg1\"] = \"test1\"\n    blackboard[\"msg2\"] = \"test2\"\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[SUCCEED], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"STATE1\",\n        Foo(),\n        transitions={SUCCEED: \"STATE2\"},\n        remappings={\"foo_data\": \"msg1\"},\n    )\n    sm.add_state(\n        \"STATE2\",\n        Foo(),\n        transitions={SUCCEED: \"STATE3\"},\n        remappings={\"foo_data\": \"msg2\"},\n    )\n    sm.add_state(\n        \"STATE3\",\n        BarState(),\n        transitions={SUCCEED: SUCCEED},\n        remappings={\"bar_data\": \"foo_out_data\"},\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_REMAPPING_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm(blackboard)\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Concurrence Demo\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos concurrence_demo.py\n```\n\n```python\nimport time\nimport rclpy\n\nimport yasmin\nfrom yasmin import State, Concurrence, Blackboard, StateMachine\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_viewer import YasminViewerPub\n\n\n# Define the FooState class, inheriting from the State class\nclass FooState(State):\n    \"\"\"\n    Represents the Foo state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the FooState instance, setting up the outcomes.\n\n        Outcomes:\n            outcome1: Indicates the state should continue.\n            outcome2: Indicates the state should continue.\n            outcome3: Indicates the state should finish execution and return.\n        \"\"\"\n        super().__init__([\"outcome1\", \"outcome2\", \"outcome3\"])\n        self.counter = 0\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Foo state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution.\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state FOO\")\n        time.sleep(2)  # Simulate work by sleeping\n\n        outcome = \"\"\n\n        blackboard[\"foo_str\"] = f\"Counter: {self.counter}\"\n\n        if self.counter \u003c 3:\n            outcome = \"outcome1\"\n        elif self.counter \u003c 5:\n            outcome = \"outcome2\"\n        else:\n            outcome = \"outcome3\"\n\n        yasmin.YASMIN_LOG_INFO(\"Finishing state FOO\")\n        self.counter += 1\n        return outcome\n\n\n# Define the BarState class, inheriting from the State class\nclass BarState(State):\n    \"\"\"\n    Represents the Bar state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the BarState instance, setting up the outcome.\n\n        Outcomes:\n            outcome3: This state will always return this outcome\n        \"\"\"\n        super().__init__(outcomes=[\"outcome3\"])\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Bar state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which will always be \"outcome3\".\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state BAR\")\n        time.sleep(4)  # Simulate work by sleeping\n\n        if \"foo_str\" in blackboard:\n            yasmin.YASMIN_LOG_INFO(blackboard[\"foo_str\"])\n        else:\n            yasmin.YASMIN_LOG_INFO(\"Blackboard does not yet contain 'foo_str'\")\n\n        yasmin.YASMIN_LOG_INFO(\"Finishing state BAR\")\n\n        return \"outcome3\"\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"CONCURRENCE_DEMO\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Create states to run concurrently\n    foo_state: State = FooState()\n    bar_state: State = BarState()\n\n    # Add concurrence state\n    concurrence_state = Concurrence(\n        states={\n            \"FOO\": foo_state,\n            \"BAR\": bar_state,\n        },\n        default_outcome=\"defaulted\",\n        outcome_map={\n            \"outcome1\": {\n                \"FOO\": \"outcome1\",\n                \"BAR\": \"outcome3\",\n            },\n            \"outcome2\": {\n                \"FOO\": \"outcome2\",\n                \"BAR\": \"outcome3\",\n            },\n        },\n    )\n\n    # Add concurrent state to the FSM\n    sm.add_state(\n        \"CONCURRENCE\",\n        concurrence_state,\n        transitions={\n            \"outcome1\": \"CONCURRENCE\",\n            \"outcome2\": \"CONCURRENCE\",\n            \"defaulted\": \"outcome4\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_CONCURRENCE_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Publisher Demo (FSM + ROS 2 Publisher)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos publisher_demo.py\n```\n\n```python\nimport time\nimport rclpy\nfrom std_msgs.msg import Int32\n\nimport yasmin\nfrom yasmin import CbState, StateMachine, Blackboard\nfrom yasmin_ros import PublisherState, set_ros_loggers\nfrom yasmin_ros.basic_outcomes import SUCCEED\nfrom yasmin_viewer import YasminViewerPub\n\n\nclass PublishIntState(PublisherState):\n    \"\"\"\n    PublishIntState is a YASMIN ROS publisher state that sends incrementing integers\n    to the 'count' topic using std_msgs.msg.Int32 messages.\n\n    This state increments a counter on the blackboard and publishes it.\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        Initializes the PublishIntState with the topic 'count' and a message creation callback.\n        \"\"\"\n        super().__init__(Int32, \"count\", self.create_int_msg)\n\n    def create_int_msg(self, blackboard: Blackboard) -\u003e Int32:\n        \"\"\"\n        Generates a std_msgs.msg.Int32 message with an incremented counter value.\n\n        Args:\n            blackboard (Blackboard): The shared data store between states.\n\n        Returns:\n            Int32: A ROS message containing the updated counter.\n        \"\"\"\n        # Get and increment the counter from the blackboard\n        counter = blackboard.get(\"counter\")\n        counter += 1\n        blackboard.set(\"counter\", counter)\n\n        # Log the message creation\n        yasmin.YASMIN_LOG_INFO(f\"Creating message {counter}\")\n\n        # Create and return the message\n        msg = Int32()\n        msg.data = counter\n        return msg\n\n\ndef check_count(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Checks the current counter against a max threshold to determine state transition.\n\n    Args:\n        blackboard (Blackboard): The shared data store between states.\n\n    Returns:\n        str: The outcome string ('outcome1' or 'outcome2').\n    \"\"\"\n    # Simulate processing time\n    time.sleep(1)\n\n    # Retrieve the counter and max value from blackboard\n    count = blackboard.get(\"counter\")\n    max_count = blackboard.get(\"max_count\")\n\n    yasmin.YASMIN_LOG_INFO(f\"Checking count: {count}\")\n\n    # Determine and return the outcome based on the counter value\n    if count \u003e= max_count:\n        return \"outcome1\"\n    else:\n        return \"outcome2\"\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_publisher_demo\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine([SUCCEED], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"PUBLISHING_INT\",\n        PublishIntState(),\n        {\n            SUCCEED: \"CHECKING_COUNTS\",\n        },\n    )\n    sm.add_state(\n        \"CHECKING_COUNTS\",\n        CbState([\"outcome1\", \"outcome2\"], check_count),\n        {\n            \"outcome1\": SUCCEED,\n            \"outcome2\": \"PUBLISHING_INT\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_PUBLISHER_DEMO\")\n\n    # Initialize blackboard with counter values\n    blackboard = Blackboard()\n    blackboard.set(\"counter\", 0)\n    blackboard.set(\"max_count\", 10)\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n#### Monitor Demo (FSM + ROS 2 Subscriber)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos monitor_demo.py\n```\n\n```python\nimport rclpy\nfrom rclpy.qos import qos_profile_sensor_data\nfrom nav_msgs.msg import Odometry\n\nimport yasmin\nfrom yasmin import Blackboard, StateMachine\nfrom yasmin_ros import MonitorState\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros.basic_outcomes import TIMEOUT\nfrom yasmin_viewer import YasminViewerPub\n\n\nclass PrintOdometryState(MonitorState):\n    \"\"\"\n    MonitorState subclass to handle Odometry messages.\n\n    This state monitors Odometry messages from the specified ROS topic,\n    logging them and transitioning based on the number of messages received.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the PrintOdometryState.\n        \"\"\"\n        super().__init__(\n            Odometry,  # msg type\n            \"odom\",  # topic name\n            [\"outcome1\", \"outcome2\"],  # outcomes\n            self.monitor_handler,  # monitor handler callback\n            qos=qos_profile_sensor_data,  # qos for the topic subscription\n            msg_queue=10,  # queue for the monitor handler callback\n            timeout=10,  # timeout to wait for messages in seconds\n        )\n        self.times = 5\n\n    def monitor_handler(self, blackboard: Blackboard, msg: Odometry) -\u003e str:\n        \"\"\"\n        Handles incoming Odometry messages.\n\n        This method is called whenever a new Odometry message is received.\n        It logs the message, decrements the count of messages to process,\n        and determines the next state outcome.\n\n        Args:\n            blackboard (Blackboard): The shared data storage for states.\n            msg (Odometry): The incoming Odometry message.\n\n        Returns:\n            str: The next state outcome, either \"outcome1\" to continue\n                 monitoring or \"outcome2\" to transition to the next state.\n\n        Exceptions:\n            None\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(msg)\n\n        self.times -= 1\n\n        if self.times \u003c= 0:\n            return \"outcome2\"\n\n        return \"outcome1\"\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 logs\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_monitor_demo\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"PRINTING_ODOM\",\n        PrintOdometryState(),\n        transitions={\n            \"outcome1\": \"PRINTING_ODOM\",\n            \"outcome2\": \"outcome4\",\n            TIMEOUT: \"outcome4\",\n            CANCEL: \"outcome4\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_MONITOR_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Service Demo (FSM + ROS 2 Service Client)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos add_two_ints_server\n```\n\n```shell\nros2 run yasmin_demos service_client_demo.py\n```\n\n```python\nimport rclpy\nfrom example_interfaces.srv import AddTwoInts\n\nimport yasmin\nfrom yasmin import CbState, Blackboard, StateMachine\nfrom yasmin_ros import ServiceState\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros.basic_outcomes import SUCCEED, ABORT\nfrom yasmin_viewer import YasminViewerPub\n\n\nclass AddTwoIntsState(ServiceState):\n    \"\"\"\n    A state that calls the AddTwoInts service to add two integers.\n\n    This class is a state in a finite state machine that sends a request\n    to the AddTwoInts service, retrieves the response, and updates the\n    blackboard with the result.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the AddTwoIntsState.\n\n        Calls the parent constructor with the specific service type,\n        service name, request handler, outcomes, and response handler.\n        \"\"\"\n        super().__init__(\n            AddTwoInts,  # srv type\n            \"/add_two_ints\",  # service name\n            self.create_request_handler,  # cb to create the request\n            [\"outcome1\"],  # outcomes. Includes (SUCCEED, ABORT)\n            self.response_handler,  # cb to process the response\n        )\n\n    def create_request_handler(self, blackboard: Blackboard) -\u003e AddTwoInts.Request:\n        \"\"\"\n        Creates the service request from the blackboard data.\n\n        Args:\n            blackboard (Blackboard): The blackboard containing the input values.\n\n        Returns:\n            AddTwoInts.Request: The request object populated with values from the blackboard.\n        \"\"\"\n        req = AddTwoInts.Request()\n        req.a = blackboard[\"a\"]\n        req.b = blackboard[\"b\"]\n        return req\n\n    def response_handler(\n        self, blackboard: Blackboard, response: AddTwoInts.Response\n    ) -\u003e str:\n        \"\"\"\n        Processes the response from the AddTwoInts service.\n\n        Updates the blackboard with the sum result from the response.\n\n        Args:\n            blackboard (Blackboard): The blackboard to update with the sum.\n            response (AddTwoInts.Response): The response from the service call.\n\n        Returns:\n            str: The outcome of the operation, which is \"outcome1\".\n        \"\"\"\n        blackboard[\"sum\"] = response.sum\n        return \"outcome1\"\n\n\ndef set_ints(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Sets the integer values in the blackboard.\n\n    This function initializes the blackboard with two integer values to be added.\n\n    Args:\n        blackboard (Blackboard): The blackboard to update with integer values.\n\n    Returns:\n        str: The outcome of the operation, which is SUCCEED.\n    \"\"\"\n    blackboard[\"a\"] = 10\n    blackboard[\"b\"] = 5\n    return SUCCEED\n\n\ndef print_sum(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Logs the sum value from the blackboard.\n\n    This function retrieves the sum from the blackboard and logs it.\n\n    Args:\n        blackboard (Blackboard): The blackboard from which to retrieve the sum.\n\n    Returns:\n        str: The outcome of the operation, which is SUCCEED.\n    \"\"\"\n    yasmin.YASMIN_LOG_INFO(f\"Sum: {blackboard['sum']}\")\n    return SUCCEED\n\n\ndef main() -\u003e None:\n    # Init ROS 2\n    rclpy.init()\n\n    # Set ROS 2 logs\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_service_client_demo\")\n\n    # Create a FSM\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Add states\n    sm.add_state(\n        \"SETTING_INTS\",\n        CbState([SUCCEED], set_ints),\n        transitions={SUCCEED: \"ADD_TWO_INTS\"},\n    )\n    sm.add_state(\n        \"ADD_TWO_INTS\",\n        AddTwoIntsState(),\n        transitions={\n            \"outcome1\": \"PRINTING_SUM\",\n            SUCCEED: \"outcome4\",\n            ABORT: \"outcome4\",\n        },\n    )\n    sm.add_state(\n        \"PRINTING_SUM\",\n        CbState([SUCCEED], print_sum),\n        transitions={\n            SUCCEED: \"outcome4\",\n        },\n    )\n\n    # Publish FSM info\n    YasminViewerPub(sm, \"YASMIN_SERVICE_CLIENT_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Action Demo (FSM + ROS 2 Action)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos fibonacci_action_server\n```\n\n```shell\nros2 run yasmin_demos action_client_demo.py\n```\n\n```python\nimport rclpy\nfrom example_interfaces.action import Fibonacci\n\nimport yasmin\nfrom yasmin import CbState, Blackboard, StateMachine\nfrom yasmin_ros import ActionState\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros.basic_outcomes import SUCCEED, ABORT, CANCEL\nfrom yasmin_viewer import YasminViewerPub\n\n\nclass FibonacciState(ActionState):\n    \"\"\"\n    Class representing the state of the Fibonacci action.\n\n    Inherits from ActionState and implements methods to handle the\n    Fibonacci action in a finite state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the FibonacciState.\n\n        Sets up the action type and the action name for the Fibonacci\n        action. Initializes goal, response handler, and feedback\n        processing callbacks.\n        \"\"\"\n        super().__init__(\n            Fibonacci,  # action type\n            \"/fibonacci\",  # action name\n            self.create_goal_handler,  # callback to create the goal\n            None,  # outcomes. Includes (SUCCEED, ABORT, CANCEL)\n            self.response_handler,  # callback to process the response\n            self.print_feedback,  # callback to process the feedback\n        )\n\n    def create_goal_handler(self, blackboard: Blackboard) -\u003e Fibonacci.Goal:\n        \"\"\"\n        Creates the goal for the Fibonacci action.\n\n        This method retrieves the input value from the blackboard and\n        populates the Fibonacci goal.\n\n        Args:\n            blackboard (Blackboard): The blackboard containing the state\n            information.\n\n        Returns:\n            Fibonacci.Goal: The populated goal object for the Fibonacci action.\n\n        Raises:\n            KeyError: If the expected key is not present in the blackboard.\n        \"\"\"\n        goal = Fibonacci.Goal()\n        goal.order = blackboard[\"n\"]  # Retrieve the input value 'n' from the blackboard\n        return goal\n\n    def response_handler(self, blackboard: Blackboard, response: Fibonacci.Result) -\u003e str:\n        \"\"\"\n        Handles the response from the Fibonacci action.\n\n        This method processes the result of the Fibonacci action and\n        stores it in the blackboard.\n\n        Args:\n            blackboard (Blackboard): The blackboard to store the result.\n            response (Fibonacci.Result): The result object from the Fibonacci action.\n\n        Returns:\n            str: Outcome of the operation, typically SUCCEED.\n\n        Raises:\n            None\n        \"\"\"\n        blackboard[\"fibo_res\"] = (\n            response.sequence\n        )  # Store the result sequence in the blackboard\n        return SUCCEED\n\n    def print_feedback(\n        self, blackboard: Blackboard, feedback: Fibonacci.Feedback\n    ) -\u003e None:\n        \"\"\"\n        Prints feedback from the Fibonacci action.\n\n        This method logs the partial sequence received during the action.\n\n        Args:\n            blackboard (Blackboard): The blackboard (not used in this method).\n            feedback (Fibonacci.Feedback): The feedback object from the Fibonacci action.\n\n        Returns:\n            None\n\n        Raises:\n            None\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(f\"Received feedback: {list(feedback.sequence)}\")\n\n\ndef print_result(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Prints the result of the Fibonacci action.\n\n    This function logs the final result stored in the blackboard.\n\n    Args:\n        blackboard (Blackboard): The blackboard containing the result.\n\n    Returns:\n        str: Outcome of the operation, typically SUCCEED.\n\n    Raises:\n        None\n    \"\"\"\n    yasmin.YASMIN_LOG_INFO(f\"Result: {blackboard['fibo_res']}\")\n    return SUCCEED\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set up ROS 2 logs\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_action_client_demo\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"CALLING_FIBONACCI\",\n        FibonacciState(),\n        transitions={\n            SUCCEED: \"PRINTING_RESULT\",\n            CANCEL: \"outcome4\",\n            ABORT: \"outcome4\",\n        },\n    )\n    sm.add_state(\n        \"PRINTING_RESULT\",\n        CbState([SUCCEED], print_result),\n        transitions={\n            SUCCEED: \"outcome4\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_ACTION_CLIENT_DEMO\")\n\n    # Create an initial blackboard with the input value\n    blackboard = Blackboard()\n    blackboard[\"n\"] = 10  # Set the Fibonacci order to 10\n\n    # Execute the FSM\n    try:\n        outcome = sm(blackboard)\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n\u003c/details\u003e\n\n#### Parameters Demo (FSM + ROS 2 Parameters)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos parameters_demo.py --ros-args -p max_counter:=5\n```\n\n```python\nimport time\nimport rclpy\n\nimport yasmin\nfrom yasmin import State, Blackboard, StateMachine\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros import GetParametersState\nfrom yasmin_ros.basic_outcomes import SUCCEED, ABORT\nfrom yasmin_viewer import YasminViewerPub\n\n\n# Define the FooState class, inheriting from the State class\nclass FooState(State):\n    \"\"\"\n    Represents the Foo state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the FooState instance, setting up the outcomes.\n\n        Outcomes:\n            outcome1: Indicates the state should continue to the Bar state.\n            outcome2: Indicates the state should finish execution and return.\n        \"\"\"\n        super().__init__([\"outcome1\", \"outcome2\"])\n        self.counter = 0\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Foo state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which can be \"outcome1\" or \"outcome2\".\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state FOO\")\n        time.sleep(3)  # Simulate work by sleeping\n\n        if self.counter \u003c blackboard[\"max_counter\"]:\n            self.counter += 1\n            blackboard[\"foo_str\"] = f\"{blackboard['counter_str']}: {self.counter}\"\n            return \"outcome1\"\n        else:\n            return \"outcome2\"\n\n\n# Define the BarState class, inheriting from the State class\nclass BarState(State):\n    \"\"\"\n    Represents the Bar state in the state machine.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the BarState instance, setting up the outcome.\n\n        Outcomes:\n            outcome3: Indicates the state should transition back to the Foo state.\n        \"\"\"\n        super().__init__(outcomes=[\"outcome3\"])\n\n    def execute(self, blackboard: Blackboard) -\u003e str:\n        \"\"\"\n        Executes the logic for the Bar state.\n\n        Args:\n            blackboard (Blackboard): The shared data structure for states.\n\n        Returns:\n            str: The outcome of the execution, which will always be \"outcome3\".\n\n        Raises:\n            Exception: May raise exceptions related to state execution.\n        \"\"\"\n        yasmin.YASMIN_LOG_INFO(\"Executing state BAR\")\n        time.sleep(3)  # Simulate work by sleeping\n\n        yasmin.YASMIN_LOG_INFO(blackboard[\"foo_str\"])\n        return \"outcome3\"\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_parameters_demo\")\n\n    # Create a finite state machine (FSM)\n    sm = StateMachine(outcomes=[\"outcome4\"], handle_sigint=True)\n\n    # Add states to the FSM\n    sm.add_state(\n        \"GETTING_PARAMETERS\",\n        GetParametersState(\n            parameters={\n                \"max_counter\": 3,\n                \"counter_str\": \"Counter\",\n            },\n        ),\n        transitions={\n            SUCCEED: \"FOO\",\n            ABORT: \"outcome4\",\n        },\n    )\n\n    sm.add_state(\n        \"FOO\",\n        FooState(),\n        transitions={\n            \"outcome1\": \"BAR\",\n            \"outcome2\": \"outcome4\",\n        },\n    )\n    sm.add_state(\n        \"BAR\",\n        BarState(),\n        transitions={\n            \"outcome3\": \"FOO\",\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_PARAMETERS_DEMO\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Factory Demo (Plugins)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n\u003e **Note:** When mixing Python and C++ states in the same state machine, they can communicate through the blackboard, but only with primitive data types: `int`, `float`, `bool`, and `string`. Complex objects or ROS messages cannot be directly shared between Python and C++ states.\n\n```shell\nros2 run yasmin_demos factory_demo.py\n```\n\n```xml\n\u003cStateMachine outcomes=\"outcome4\"\u003e\n    \u003cState name=\"Foo\" type=\"cpp\" class=\"yasmin_demos/FooState\"\u003e\n        \u003cTransition from=\"outcome1\" to=\"Bar\"/\u003e\n        \u003cTransition from=\"outcome2\" to=\"outcome4\"/\u003e\n    \u003c/State\u003e\n    \u003cState name=\"Bar\" type=\"py\" module=\"yasmin_demos.bar_state\" class=\"BarState\"\u003e\n        \u003cTransition from=\"outcome3\" to=\"Foo\"/\u003e\n    \u003c/State\u003e\n\u003c/StateMachine\u003e\n```\n\n```python\nimport os\nimport rclpy\nimport yasmin\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_viewer import YasminViewerPub\nfrom yasmin_factory import YasminFactory\nfrom ament_index_python import get_package_share_directory\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_demo\")\n\n    # Create a finite state machine (FSM)\n    factory = YasminFactory()\n    sm = factory.create_sm_from_file(\n        os.path.join(\n            get_package_share_directory(\"yasmin_demos\"), \"state_machines\", \"demo_1.xml\"\n        )\n    )\n    sm.set_sigint_handler(True)\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"plugin_demo\")\n\n    # Execute the FSM\n    try:\n        outcome = sm()\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n#### Nav2 Demo (Hierarchical FSM + ROS 2 Action)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```python\nimport random\nimport rclpy\nfrom geometry_msgs.msg import Pose\nfrom nav2_msgs.action import NavigateToPose\n\nimport yasmin\nfrom yasmin import CbState, Blackboard, StateMachine\nfrom yasmin_ros import ActionState\nfrom yasmin_ros import set_ros_loggers\nfrom yasmin_ros.basic_outcomes import SUCCEED, ABORT, CANCEL\nfrom yasmin_viewer import YasminViewerPub\n\n# Constants for state outcomes\nHAS_NEXT = \"has_next\"  ##\u003c Indicates there are more waypoints\nEND = \"end\"  ##\u003c Indicates no more waypoints\n\n\nclass Nav2State(ActionState):\n    \"\"\"\n    ActionState for navigating to a specified pose using ROS 2 Navigation.\n    \"\"\"\n\n    def __init__(self) -\u003e None:\n        \"\"\"\n        Initializes the Nav2State.\n\n        Calls the parent constructor to set up the action with:\n        - Action type: NavigateToPose\n        - Action name: /navigate_to_pose\n        - Callback for goal creation: create_goal_handler\n        - Outcomes: None, since it will use default outcomes (SUCCEED, ABORT, CANCEL)\n        \"\"\"\n        super().__init__(\n            NavigateToPose,  # action type\n            \"/navigate_to_pose\",  # action name\n            self.create_goal_handler,  # callback to create the goal\n            None,  # outcomes\n            None,  # callback to process the response\n        )\n\n    def create_goal_handler(self, blackboard: Blackboard) -\u003e NavigateToPose.Goal:\n        \"\"\"\n        Creates a goal for navigation based on the current pose in the blackboard.\n\n        Args:\n            blackboard (Blackboard): The blackboard instance holding current state data.\n\n        Returns:\n            NavigateToPose.Goal: The constructed goal for the navigation action.\n        \"\"\"\n        goal = NavigateToPose.Goal()\n        goal.pose.pose = blackboard[\"pose\"]\n        goal.pose.header.frame_id = \"map\"  # Set the reference frame to 'map'\n        return goal\n\n\ndef create_waypoints(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Initializes waypoints in the blackboard for navigation.\n\n    Args:\n        blackboard (Blackboard): The blackboard instance to store waypoints.\n\n    Returns:\n        str: Outcome indicating success (SUCCEED).\n    \"\"\"\n    blackboard[\"waypoints\"] = {\n        \"entrance\": [1.25, 6.30, -0.78, 0.67],\n        \"bathroom\": [4.89, 1.64, 0.0, 1.0],\n        \"livingroom\": [1.55, 4.03, -0.69, 0.72],\n        \"kitchen\": [3.79, 6.77, 0.99, 0.12],\n        \"bedroom\": [7.50, 4.89, 0.76, 0.65],\n    }\n    return SUCCEED\n\n\ndef take_random_waypoint(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Selects a random set of waypoints from the available waypoints.\n\n    Args:\n        blackboard (Blackboard): The blackboard instance to store random waypoints.\n\n    Returns:\n        str: Outcome indicating success (SUCCEED).\n    \"\"\"\n    blackboard[\"random_waypoints\"] = random.sample(\n        list(blackboard[\"waypoints\"].keys()), blackboard[\"waypoints_num\"]\n    )\n    return SUCCEED\n\n\ndef get_next_waypoint(blackboard: Blackboard) -\u003e str:\n    \"\"\"\n    Retrieves the next waypoint from the list of random waypoints.\n\n    Updates the blackboard with the pose of the next waypoint.\n\n    Args:\n        blackboard (Blackboard): The blackboard instance holding current state data.\n\n    Returns:\n        str: Outcome indicating whether there is a next waypoint (HAS_NEXT) or if\n             navigation is complete (END).\n    \"\"\"\n    if not blackboard[\"random_waypoints\"]:\n        return END\n\n    wp_name = blackboard[\"random_waypoints\"].pop(0)  # Get the next waypoint name\n    wp = blackboard[\"waypoints\"][wp_name]  # Get the waypoint coordinates\n\n    pose = Pose()\n    pose.position.x = wp[0]\n    pose.position.y = wp[1]\n    pose.orientation.z = wp[2]\n    pose.orientation.w = wp[3]\n\n    blackboard[\"pose\"] = pose  # Update blackboard with new pose\n    blackboard[\"text\"] = f\"I have reached waypoint {wp_name}\"\n\n    return HAS_NEXT\n\n\ndef main() -\u003e None:\n    # Initialize ROS 2\n    rclpy.init()\n\n    # Set ROS 2 loggers for debugging\n    set_ros_loggers()\n    yasmin.YASMIN_LOG_INFO(\"yasmin_nav2_demo\")\n\n    # Create state machines\n    sm = StateMachine(outcomes=[SUCCEED, ABORT, CANCEL], handle_sigint=True)\n    nav_sm = StateMachine(outcomes=[SUCCEED, ABORT, CANCEL])\n\n    # Add states to the state machine\n    sm.add_state(\n        \"CREATING_WAYPOINTS\",\n        CbState([SUCCEED], create_waypoints),\n        transitions={\n            SUCCEED: \"TAKING_RANDOM_WAYPOINTS\",\n        },\n    )\n    sm.add_state(\n        \"TAKING_RANDOM_WAYPOINTS\",\n        CbState([SUCCEED], take_random_waypoint),\n        transitions={\n            SUCCEED: \"NAVIGATING\",\n        },\n    )\n    nav_sm.add_state(\n        \"GETTING_NEXT_WAYPOINT\",\n        CbState([END, HAS_NEXT], get_next_waypoint),\n        transitions={\n            END: SUCCEED,\n            HAS_NEXT: \"NAVIGATING\",\n        },\n    )\n    nav_sm.add_state(\n        \"NAVIGATING\",\n        Nav2State(),\n        transitions={\n            SUCCEED: \"GETTING_NEXT_WAYPOINT\",\n            CANCEL: CANCEL,\n            ABORT: ABORT,\n        },\n    )\n    sm.add_state(\n        \"NAVIGATING\",\n        nav_sm,\n        transitions={\n            SUCCEED: SUCCEED,\n            CANCEL: CANCEL,\n            ABORT: ABORT,\n        },\n    )\n\n    # Publish FSM information for visualization\n    YasminViewerPub(sm, \"YASMIN_NAV2_DEMO\")\n\n    # Execute the state machine\n    blackboard = Blackboard()\n    blackboard[\"waypoints_num\"] = 2  # Set the number of waypoints to navigate\n\n    # Execute the FSM\n    try:\n        outcome = sm(blackboard)\n        yasmin.YASMIN_LOG_INFO(outcome)\n    except Exception as e:\n        yasmin.YASMIN_LOG_WARN(e)\n\n    # Shutdown ROS 2 if it's running\n    if rclpy.ok():\n        rclpy.shutdown()\n\nif __name__ == \"__main__\":\n    main()\n```\n\n\u003c/details\u003e\n\n### Cpp\n\n#### Vanilla Demo\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos yasmin_demo\n```\n\n```cpp\n#include \u003cchrono\u003e\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\n/**\n * @brief Represents the \"Foo\" state in the state machine.\n *\n * This state increments a counter each time it is executed and\n * communicates the current count via the blackboard.\n */\nclass FooState : public yasmin::State {\npublic:\n  /// Counter to track the number of executions.\n  int counter;\n\n  /**\n   * @brief Constructs a FooState object, initializing the counter.\n   */\n  FooState() : yasmin::State({\"outcome1\", \"outcome2\"}), counter(0){};\n\n  /**\n   * @brief Executes the Foo state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * increments the counter, and sets a string in the blackboard.\n   * The state will transition to either \"outcome1\" or \"outcome2\"\n   * based on the current value of the counter.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome1\" or \"outcome2\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state FOO\");\n    std::this_thread::sleep_for(std::chrono::seconds(3));\n\n    if (this-\u003ecounter \u003c 3) {\n      this-\u003ecounter += 1;\n      blackboard-\u003eset\u003cstd::string\u003e(\"foo_str\",\n                                   \"Counter: \" + std::to_string(this-\u003ecounter));\n      return \"outcome1\";\n\n    } else {\n      return \"outcome2\";\n    }\n  };\n};\n\n/**\n * @brief Represents the \"Bar\" state in the state machine.\n *\n * This state logs the value from the blackboard and provides\n * a single outcome to transition.\n */\nclass BarState : public yasmin::State {\npublic:\n  /**\n   * @brief Constructs a BarState object.\n   */\n  BarState() : yasmin::State({\"outcome3\"}) {}\n\n  /**\n   * @brief Executes the Bar state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * retrieves a string from the blackboard, and logs it.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome3\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state BAR\");\n    std::this_thread::sleep_for(std::chrono::seconds(3));\n\n    YASMIN_LOG_INFO(blackboard-\u003eget\u003cstd::string\u003e(\"foo_str\").c_str());\n\n    return \"outcome3\";\n  }\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logs\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_demo\");\n\n  // Create a state machine\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\"FOO\", std::make_shared\u003cFooState\u003e(),\n                {\n                    {\"outcome1\", \"BAR\"},\n                    {\"outcome2\", \"outcome4\"},\n                });\n  sm-\u003eadd_state(\"BAR\", std::make_shared\u003cBarState\u003e(),\n                {\n                    {\"outcome3\", \"FOO\"},\n                });\n\n  // Publish state machine updates\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_DEMO\");\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Blackboard Remapping Demo\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos remap_demo\n```\n\n```cpp\n#include \u003cchrono\u003e\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\n/**\n * @brief Represents the \"Foo\" state in the state machine.\n */\nclass FooState : public yasmin::State {\npublic:\n  /**\n   * @brief Constructs a FooState object, initializing the counter.\n   */\n  FooState() : yasmin::State({yasmin_ros::basic_outcomes::SUCCEED}){};\n\n  /**\n   * @brief Executes the Foo state logic.\n   *\n   * Executes the logic for the Foo state.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution, which can be SUCCEED.\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    std::string data = blackboard-\u003eget\u003cstd::string\u003e(\"foo_data\");\n    YASMIN_LOG_INFO(\"%s\", data.c_str());\n    blackboard-\u003eset\u003cstd::string\u003e(\"foo_out_data\", data);\n    return yasmin_ros::basic_outcomes::SUCCEED;\n  };\n};\n\n/**\n * @brief Represents the \"Bar\" state in the state machine.\n */\nclass BarState : public yasmin::State {\npublic:\n  /**\n   * @brief Constructs a BarState object.\n   */\n  BarState() : yasmin::State({yasmin_ros::basic_outcomes::SUCCEED}) {}\n\n  /**\n   * @brief Executes the Bar state logic.\n   *\n   * Executes the logic for the Bar state.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome3\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    std::string datga = blackboard-\u003eget\u003cstd::string\u003e(\"bar_data\");\n    YASMIN_LOG_INFO(\"%s\", datga.c_str());\n    return yasmin_ros::basic_outcomes::SUCCEED;\n  }\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logs\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_remapping_demo\");\n\n  // Create blackboard\n  auto blackboard = yasmin::Blackboard::make_shared();\n  blackboard-\u003eset\u003cstd::string\u003e(\"msg1\", \"test1\");\n  blackboard-\u003eset\u003cstd::string\u003e(\"msg2\", \"test2\");\n\n  // Create a state machine\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{yasmin_ros::basic_outcomes::SUCCEED},\n      true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\"STATE1\", std::make_shared\u003cFooState\u003e(),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"STATE2\"},\n                },\n                {\n                    {\"foo_data\", \"msg1\"},\n                });\n  sm-\u003eadd_state(\"STATE2\", std::make_shared\u003cFooState\u003e(),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"STATE3\"},\n                },\n                {\n                    {\"foo_data\", \"msg2\"},\n                });\n  sm-\u003eadd_state(\"STATE3\", std::make_shared\u003cBarState\u003e(),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED,\n                     yasmin_ros::basic_outcomes::SUCCEED},\n                },\n                {\n                    {\"bar_data\", \"foo_out_data\"},\n                });\n\n  // Publish state machine updates\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_REMAPPING_DEMO\");\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())(blackboard);\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Concurrence Demo\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos concurrence_demo\n```\n\n```cpp\n#include \u003cchrono\u003e\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"yasmin/concurrence.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\n/**\n * @brief Represents the \"Foo\" state in the state machine.\n *\n * This state increments a counter each time it is executed and\n * communicates the current count via the blackboard.\n */\nclass FooState : public yasmin::State {\npublic:\n  /// Counter to track the number of executions.\n  int counter;\n\n  /**\n   * @brief Constructs a FooState object, initializing the counter.\n   */\n  FooState()\n      : yasmin::State({\"outcome1\", \"outcome2\", \"outcome3\"}), counter(0){};\n\n  /**\n   * @brief Executes the Foo state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * increments the counter, and sets a string in the blackboard.\n   * The state will transition to either \"outcome1\" or \"outcome2\"\n   * based on the current value of the counter.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome1\" or \"outcome2\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state FOO\");\n    std::this_thread::sleep_for(std::chrono::seconds(2));\n\n    std::string outcome;\n\n    blackboard-\u003eset\u003cstd::string\u003e(\"foo_str\",\n                                 \"Counter: \" + std::to_string(this-\u003ecounter));\n\n    if (this-\u003ecounter \u003c 3) {\n      outcome = \"outcome1\";\n    } else if (this-\u003ecounter \u003c 5) {\n      outcome = \"outcome2\";\n    } else {\n      outcome = \"outcome3\";\n    }\n\n    YASMIN_LOG_INFO(\"Finishing state FOO\");\n    this-\u003ecounter += 1;\n    return outcome;\n  };\n};\n\n/**\n * @brief Represents the \"Bar\" state in the state machine.\n *\n * This state logs the value from the blackboard and provides\n * a single outcome to transition.\n */\nclass BarState : public yasmin::State {\npublic:\n  /**\n   * @brief Constructs a BarState object.\n   */\n  BarState() : yasmin::State({\"outcome3\"}) {}\n\n  /**\n   * @brief Executes the Bar state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * retrieves a string from the blackboard, and logs it.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome3\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state BAR\");\n    std::this_thread::sleep_for(std::chrono::seconds(4));\n\n    if (blackboard-\u003econtains(\"foo_str\")) {\n      YASMIN_LOG_INFO(blackboard-\u003eget\u003cstd::string\u003e(\"foo_str\").c_str());\n    } else {\n      YASMIN_LOG_INFO(\"blackboard does not yet contains 'foo_str'\");\n    }\n\n    YASMIN_LOG_INFO(\"Finishing state BAR\");\n\n    return \"outcome3\";\n  }\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logs\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_concurrence_demo\");\n\n  // Create a state machine\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Create states to run concurrently\n  auto foo_state = std::make_shared\u003cFooState\u003e();\n  auto bar_state = std::make_shared\u003cBarState\u003e();\n\n  // Create concurrent state\n  auto concurrent_state = yasmin::Concurrence::make_shared(\n      yasmin::StateMap{\n          {\"FOO\", foo_state},\n          {\"BAR\", bar_state},\n      },\n      \"defaulted\",\n      yasmin::OutcomeMap{\n          {\"outcome1\", {{\"FOO\", \"outcome1\"}, {\"BAR\", \"outcome3\"}}},\n          {\"outcome2\", {{\"FOO\", \"outcome2\"}, {\"BAR\", \"outcome3\"}}},\n      });\n\n  // Add concurrent state to the state machine\n  sm-\u003eadd_state(\"CONCURRENCE\", concurrent_state,\n                {\n                    {\"outcome1\", \"CONCURRENCE\"},\n                    {\"outcome2\", \"CONCURRENCE\"},\n                    {\"defaulted\", \"outcome4\"},\n                });\n\n  // Publish state machine updates\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_CONCURRENCE_DEMO\");\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Publisher Demo (FSM + ROS 2 Publisher)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos publisher_demo\n```\n\n```cpp\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"std_msgs/msg/int32.hpp\"\n\n#include \"yasmin/cb_state.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/publisher_state.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\n\n/**\n * @class PublishIntState\n * @brief A state that publishes ints.\n *\n * This class inherits from yasmin_ros::PublisherState and publish ints\n * to the \"count\" topic.\n */\nclass PublishIntState\n    : public yasmin_ros::PublisherState\u003cstd_msgs::msg::Int32\u003e {\n\npublic:\n  /**\n   * @brief Constructor for the PublishIntState class.\n   */\n  PublishIntState()\n      : yasmin_ros::PublisherState\u003cstd_msgs::msg::Int32\u003e(\n            \"count\", // topic name\n            std::bind(\u0026PublishIntState::create_int_msg, this,\n                      _1) // create msg handler callback\n        ){};\n\n  /**\n   * @brief Create a new Int message.\n   *\n   *\n   * @param blackboard Shared pointer to the blackboard (unused in this\n   * implementation).\n   * @return A new Int message.\n   */\n  std_msgs::msg::Int32\n  create_int_msg(yasmin::Blackboard::SharedPtr blackboard) {\n\n    int counter = blackboard-\u003eget\u003cint\u003e(\"counter\");\n    counter++;\n    blackboard-\u003eset\u003cint\u003e(\"counter\", counter);\n\n    YASMIN_LOG_INFO(\"Creating message %d\", counter);\n    std_msgs::msg::Int32 msg;\n    msg.data = counter;\n    return msg;\n  };\n};\n\n/**\n * @brief Check the count in the blackboard and return an outcome based on it.\n *\n * This function checks the value of \"counter\" in the blackboard and compares it\n * with \"max_count\". If \"counter\" exceeds \"max_count\", it returns \"outcome1\",\n * otherwise it returns \"outcome2\".\n *\n * @param blackboard Shared pointer to the blackboard.\n * @return A string representing the outcome.\n */\nstd::string\ncheck_count(yasmin::Blackboard::SharedPtr blackboard) {\n\n  // Sleep for 1 second to simulate some processing time\n  rclcpp::sleep_for(std::chrono::seconds(1));\n  YASMIN_LOG_INFO(\"Checking count: %d\", blackboard-\u003eget\u003cint\u003e(\"counter\"));\n\n  if (blackboard-\u003eget\u003cint\u003e(\"counter\") \u003e= blackboard-\u003eget\u003cint\u003e(\"max_count\")) {\n    return \"outcome1\";\n  } else {\n    return \"outcome2\";\n  }\n}\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set up ROS 2 loggers\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_publisher_demo\");\n\n  // Create a state machine with a final outcome\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{yasmin_ros::basic_outcomes::SUCCEED},\n      true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\"PUBLISHING_INT\", std::make_shared\u003cPublishIntState\u003e(),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED,\n                     \"CHECKINNG_COUNTS\"}, // Transition back to itself\n                });\n  sm-\u003eadd_state(\"CHECKINNG_COUNTS\",\n                yasmin::CbState::make_shared(\n                    std::initializer_list\u003cstd::string\u003e{\"outcome1\", \"outcome2\"},\n                    check_count),\n                {{\"outcome1\", yasmin_ros::basic_outcomes::SUCCEED},\n                 {\"outcome2\", \"PUBLISHING_INT\"}});\n\n  // Publisher for visualizing the state machine's status\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_PUBLISHER_DEMO\");\n\n  // Execute the state machine\n  yasmin::Blackboard::SharedPtr blackboard =\n      yasmin::Blackboard::make_shared();\n  blackboard-\u003eset\u003cint\u003e(\"counter\", 0);\n  blackboard-\u003eset\u003cint\u003e(\"max_count\", 10);\n  try {\n    std::string outcome = (*sm.get())(blackboard);\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Monitor Demo (FSM + ROS 2 Subscriber)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos monitor_demo\n```\n\n```cpp\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"nav_msgs/msg/odometry.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/monitor_state.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\n\n/**\n * @class PrintOdometryState\n * @brief A state that monitors odometry data and transitions based on a\n * specified count.\n *\n * This class inherits from yasmin_ros::MonitorState and listens to the \"odom\"\n * topic for nav_msgs::msg::Odometry messages. The state transitions once a\n * specified number of messages has been received and processed.\n */\nclass PrintOdometryState\n    : public yasmin_ros::MonitorState\u003cnav_msgs::msg::Odometry\u003e {\n\npublic:\n  /// The number of times the state will process messages\n  int times;\n\n  /**\n   * @brief Constructor for the PrintOdometryState class.\n   */\n  PrintOdometryState()\n      : yasmin_ros::MonitorState\u003cnav_msgs::msg::Odometry\u003e(\n            \"odom\",                   // topic name\n            {\"outcome1\", \"outcome2\"}, // possible outcomes\n            std::bind(\u0026PrintOdometryState::monitor_handler, this, _1,\n                      _2), // monitor handler callback\n            10,            // QoS for the topic subscription\n            10,            // queue size for the callback\n            10             // timeout for receiving messages\n        ) {\n    this-\u003etimes = 5;\n  };\n\n  /**\n   * @brief Handler for processing odometry data.\n   *\n   * This function logs the x, y, and z positions from the odometry message.\n   * After processing, it decreases the `times` counter. When the counter\n   * reaches zero, the state transitions to \"outcome2\"; otherwise, it remains in\n   * \"outcome1\".\n   *\n   * @param blackboard Shared pointer to the blackboard (unused in this\n   * implementation).\n   * @param msg Shared pointer to the received odometry message.\n   * @return A string representing the outcome: \"outcome1\" to stay in the state,\n   *         or \"outcome2\" to transition out of the state.\n   */\n  std::string\n  monitor_handler(yasmin::Blackboard::SharedPtr blackboard,\n                  std::shared_ptr\u003cnav_msgs::msg::Odometry\u003e msg) {\n\n    (void)blackboard; // blackboard is not used in this implementation\n\n    YASMIN_LOG_INFO(\"x: %f\", msg-\u003epose.pose.position.x);\n    YASMIN_LOG_INFO(\"y: %f\", msg-\u003epose.pose.position.y);\n    YASMIN_LOG_INFO(\"z: %f\", msg-\u003epose.pose.position.z);\n\n    this-\u003etimes--;\n\n    // Transition based on remaining times\n    if (this-\u003etimes \u003c= 0) {\n      return \"outcome2\";\n    }\n\n    return \"outcome1\";\n  };\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set up ROS 2 loggers\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_monitor_demo\");\n\n  // Create a state machine with a final outcome\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\n      \"PRINTING_ODOM\", std::make_shared\u003cPrintOdometryState\u003e(),\n      {\n          {\"outcome1\",\n           \"PRINTING_ODOM\"},        // Transition back to itself on outcome1\n          {\"outcome2\", \"outcome4\"}, // Transition to outcome4 on outcome2\n          {yasmin_ros::basic_outcomes::TIMEOUT,\n           \"outcome4\"}, // Timeout transition\n      });\n\n  // Publisher for visualizing the state machine's status\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_MONITOR_DEMO\");\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Service Demo (FSM + ROS 2 Service Client)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos add_two_ints_server\n```\n\n```shell\nros2 run yasmin_demos service_client_demo\n```\n\n```cpp\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"example_interfaces/srv/add_two_ints.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n\n#include \"yasmin/cb_state.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_ros/service_state.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\n\n/**\n * @brief Sets two integer values in the blackboard.\n *\n * Sets the integers \"a\" and \"b\" in the blackboard with values 10 and 5,\n * respectively.\n *\n * @param blackboard Shared pointer to the blackboard for setting values.\n * @return std::string Outcome indicating success or failure.\n */\nstd::string\nset_ints(yasmin::Blackboard::SharedPtr blackboard) {\n  blackboard-\u003eset\u003cint\u003e(\"a\", 10);\n  blackboard-\u003eset\u003cint\u003e(\"b\", 5);\n  return yasmin_ros::basic_outcomes::SUCCEED;\n}\n\n/**\n * @brief Prints the sum stored in the blackboard.\n *\n * Retrieves the integer \"sum\" from the blackboard and prints it.\n *\n * @param blackboard Shared pointer to the blackboard for getting values.\n * @return std::string Outcome indicating success.\n */\nstd::string\nprint_sum(yasmin::Blackboard::SharedPtr blackboard) {\n  std::stringstream ss;\n  ss \u003c\u003c \"Sum: \" \u003c\u003c blackboard-\u003eget\u003cint\u003e(\"sum\");\n  YASMIN_LOG_INFO(ss.str().c_str());\n  return yasmin_ros::basic_outcomes::SUCCEED;\n}\n\n/**\n * @class AddTwoIntsState\n * @brief State for calling the AddTwoInts service in ROS 2.\n *\n * This state constructs and sends a service request to add two integers, and\n * processes the response to retrieve and store the result in the blackboard.\n */\nclass AddTwoIntsState\n    : public yasmin_ros::ServiceState\u003cexample_interfaces::srv::AddTwoInts\u003e {\npublic:\n  /**\n   * @brief Constructor for AddTwoIntsState.\n   *\n   * Initializes the service state with the specified service name and handlers\n   * for request creation and response processing.\n   */\n  AddTwoIntsState()\n      : yasmin_ros::ServiceState\u003cexample_interfaces::srv::AddTwoInts\u003e(\n            \"/add_two_ints\",\n            std::bind(\u0026AddTwoIntsState::create_request_handler, this, _1),\n            {\"outcome1\"},\n            std::bind(\u0026AddTwoIntsState::response_handler, this, _1, _2)){};\n\n  /**\n   * @brief Creates a service request using values from the blackboard.\n   *\n   * Retrieves integers \"a\" and \"b\" from the blackboard and sets them in the\n   * request.\n   *\n   * @param blackboard Shared pointer to the blackboard for retrieving values.\n   * @return example_interfaces::srv::AddTwoInts::Request::SharedPtr The service\n   * request.\n   */\n  example_interfaces::srv::AddTwoInts::Request::SharedPtr\n  create_request_handler(\n      yasmin::Blackboard::SharedPtr blackboard) {\n\n    auto request =\n        std::make_shared\u003cexample_interfaces::srv::AddTwoInts::Request\u003e();\n    request-\u003ea = blackboard-\u003eget\u003cint\u003e(\"a\");\n    request-\u003eb = blackboard-\u003eget\u003cint\u003e(\"b\");\n    return request;\n  };\n\n  /**\n   * @brief Handles the service response and stores the result in the\n   * blackboard.\n   *\n   * Retrieves the sum from the service response and stores it in the\n   * blackboard.\n   *\n   * @param blackboard Shared pointer to the blackboard for storing values.\n   * @param response Shared pointer to the service response containing the sum.\n   * @return std::string Outcome indicating success.\n   */\n  std::string response_handler(\n      yasmin::Blackboard::SharedPtr blackboard,\n      example_interfaces::srv::AddTwoInts::Response::SharedPtr response) {\n\n    blackboard-\u003eset\u003cint\u003e(\"sum\", response-\u003esum);\n    return \"outcome1\";\n  };\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set up ROS 2 logging.\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_service_client_demo\");\n\n  // Create a state machine with a specified outcome.\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Add states to the state machine.\n  sm-\u003eadd_state(\"SETTING_INTS\",\n                yasmin::CbState::make_shared(\n                    std::initializer_list\u003cstd::string\u003e{\n                        yasmin_ros::basic_outcomes::SUCCEED},\n                    set_ints),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"ADD_TWO_INTS\"},\n                });\n  sm-\u003eadd_state(\"ADD_TWO_INTS\", std::make_shared\u003cAddTwoIntsState\u003e(),\n                {\n                    {\"outcome1\", \"PRINTING_SUM\"},\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"outcome4\"},\n                    {yasmin_ros::basic_outcomes::ABORT, \"outcome4\"},\n                });\n  sm-\u003eadd_state(\"PRINTING_SUM\",\n                yasmin::CbState::make_shared(\n                    std::initializer_list\u003cstd::string\u003e{\n                        yasmin_ros::basic_outcomes::SUCCEED},\n                    print_sum),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"outcome4\"},\n                });\n\n  // Publish state machine visualization.\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_SERVICE_CLIENT_DEMO\");\n\n  // Execute the state machine.\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Action Demo (FSM + ROS 2 Action)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos fibonacci_action_server\n```\n\n```shell\nros2 run yasmin_demos action_client_demo\n```\n\n```cpp\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"example_interfaces/action/fibonacci.hpp\"\n\n#include \"yasmin/cb_state.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/action_state.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_ros/yasmin_node.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\nusing Fibonacci = example_interfaces::action::Fibonacci;\n\n/**\n * @brief Prints the result of the Fibonacci action.\n *\n * Retrieves the final Fibonacci sequence from the blackboard and outputs it to\n * stderr.\n *\n * @param blackboard Shared pointer to the blackboard storing the Fibonacci\n * sequence.\n * @return The outcome status indicating success.\n */\nstd::string\nprint_result(yasmin::Blackboard::SharedPtr blackboard) {\n\n  auto fibo_res = blackboard-\u003eget\u003cstd::vector\u003cint\u003e\u003e(\"fibo_res\");\n\n  std::stringstream ss;\n  ss \u003c\u003c \"Result: [\";\n  for (size_t i = 0; i \u003c fibo_res.size(); i++) {\n    ss \u003c\u003c fibo_res[i];\n    if (i \u003c fibo_res.size() - 1) {\n      ss \u003c\u003c \", \";\n    }\n  }\n  ss \u003c\u003c \"]\";\n\n  YASMIN_LOG_INFO(ss.str().c_str());\n\n  return yasmin_ros::basic_outcomes::SUCCEED;\n}\n\n/**\n * @class FibonacciState\n * @brief Represents the action state for the Fibonacci action.\n *\n * This class manages goal creation, response handling, and feedback processing\n * for the Fibonacci action.\n */\nclass FibonacciState : public yasmin_ros::ActionState\u003cFibonacci\u003e {\n\npublic:\n  /**\n   * @brief Constructs a new FibonacciState object and initializes callbacks.\n   */\n  FibonacciState()\n      : yasmin_ros::ActionState\u003cFibonacci\u003e(\n            \"/fibonacci\",\n            std::bind(\u0026FibonacciState::create_goal_handler, this, _1),\n            std::bind(\u0026FibonacciState::response_handler, this, _1, _2),\n            std::bind(\u0026FibonacciState::print_feedback, this, _1, _2)){};\n\n  /**\n   * @brief Callback for creating the Fibonacci action goal.\n   *\n   * Reads the order of the Fibonacci sequence from the blackboard.\n   *\n   * @param blackboard Shared pointer to the blackboard.\n   * @return The Fibonacci goal with the specified order.\n   */\n  Fibonacci::Goal create_goal_handler(\n      yasmin::Blackboard::SharedPtr blackboard) {\n\n    auto goal = Fibonacci::Goal();\n    goal.order = blackboard-\u003eget\u003cint\u003e(\"n\");\n    return goal;\n  };\n\n  /**\n   * @brief Callback for handling the action response.\n   *\n   * Stores the resulting Fibonacci sequence in the blackboard.\n   *\n   * @param blackboard Shared pointer to the blackboard.\n   * @param response Shared pointer to the action result containing the\n   * sequence.\n   * @return The outcome status indicating success.\n   */\n  std::string\n  response_handler(yasmin::Blackboard::SharedPtr blackboard,\n                   Fibonacci::Result::SharedPtr response) {\n\n    blackboard-\u003eset\u003cstd::vector\u003cint\u003e\u003e(\"fibo_res\", response-\u003esequence);\n    return yasmin_ros::basic_outcomes::SUCCEED;\n  };\n\n  /**\n   * @brief Callback for printing action feedback.\n   *\n   * Displays each new partial Fibonacci sequence number as it is received.\n   *\n   * @param blackboard Shared pointer to the blackboard (not used in this\n   * method).\n   * @param feedback Shared pointer to the feedback message with partial\n   * sequence.\n   */\n  void\n  print_feedback(yasmin::Blackboard::SharedPtr blackboard,\n                 std::shared_ptr\u003cconst Fibonacci::Feedback\u003e feedback) {\n    (void)blackboard;\n\n    std::stringstream ss;\n    ss \u003c\u003c \"Received feedback: [\";\n    for (size_t i = 0; i \u003c feedback-\u003esequence.size(); i++) {\n      ss \u003c\u003c feedback-\u003esequence[i];\n      if (i \u003c feedback-\u003esequence.size() - 1) {\n        ss \u003c\u003c \", \";\n      }\n    }\n    ss \u003c\u003c \"]\";\n\n    YASMIN_LOG_INFO(ss.str().c_str());\n  };\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logging\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_action_client_demo\");\n\n  // Create the state machine\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\"CALLING_FIBONACCI\", std::make_shared\u003cFibonacciState\u003e(),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"PRINTING_RESULT\"},\n                    {yasmin_ros::basic_outcomes::CANCEL, \"outcome4\"},\n                    {yasmin_ros::basic_outcomes::ABORT, \"outcome4\"},\n                });\n  sm-\u003eadd_state(\"PRINTING_RESULT\",\n                yasmin::CbState::make_shared(\n                    std::initializer_list\u003cstd::string\u003e{\n                        yasmin_ros::basic_outcomes::SUCCEED},\n                    print_result),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"outcome4\"},\n                });\n\n  // Publisher for visualizing the state machine\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_ACTION_CLIENT_DEMO\");\n\n  // Create an initial blackboard and set the Fibonacci order\n  yasmin::Blackboard::SharedPtr blackboard =\n      yasmin::Blackboard::make_shared();\n  blackboard-\u003eset\u003cint\u003e(\"n\", 10);\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())(blackboard);\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Parameters Demo (FSM + ROS 2 Parameters)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```shell\nros2 run yasmin_demos parameters_demo --ros-args -p max_counter:=5\n```\n\n```cpp\n#include \u003cchrono\u003e\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"rclcpp/rclcpp.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/get_parameters_state.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\n/**\n * @brief Represents the \"Foo\" state in the state machine.\n *\n * This state increments a counter each time it is executed and\n * communicates the current count via the blackboard.\n */\nclass FooState : public yasmin::State {\npublic:\n  /// Counter to track the number of executions.\n  int counter;\n\n  /**\n   * @brief Constructs a FooState object, initializing the counter.\n   */\n  FooState() : yasmin::State({\"outcome1\", \"outcome2\"}), counter(0){};\n\n  /**\n   * @brief Executes the Foo state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * increments the counter, and sets a string in the blackboard.\n   * The state will transition to either \"outcome1\" or \"outcome2\"\n   * based on the current value of the counter.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome1\" or \"outcome2\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state FOO\");\n    std::this_thread::sleep_for(std::chrono::seconds(3));\n\n    if (this-\u003ecounter \u003c blackboard-\u003eget\u003cint\u003e(\"max_counter\")) {\n      this-\u003ecounter += 1;\n      blackboard-\u003eset\u003cstd::string\u003e(\"foo_str\",\n                                   blackboard-\u003eget\u003cstd::string\u003e(\"counter_str\") +\n                                       \": \" + std::to_string(this-\u003ecounter));\n      return \"outcome1\";\n\n    } else {\n      return \"outcome2\";\n    }\n  };\n};\n\n/**\n * @brief Represents the \"Bar\" state in the state machine.\n *\n * This state logs the value from the blackboard and provides\n * a single outcome to transition.\n */\nclass BarState : public yasmin::State {\npublic:\n  /**\n   * @brief Constructs a BarState object.\n   */\n  BarState() : yasmin::State({\"outcome3\"}) {}\n\n  /**\n   * @brief Executes the Bar state logic.\n   *\n   * This method logs the execution, waits for 3 seconds,\n   * retrieves a string from the blackboard, and logs it.\n   *\n   * @param blackboard Shared pointer to the blackboard for state communication.\n   * @return std::string The outcome of the execution: \"outcome3\".\n   */\n  std::string\n  execute(yasmin::Blackboard::SharedPtr blackboard) override {\n    YASMIN_LOG_INFO(\"Executing state BAR\");\n    std::this_thread::sleep_for(std::chrono::seconds(3));\n\n    YASMIN_LOG_INFO(blackboard-\u003eget\u003cstd::string\u003e(\"foo_str\").c_str());\n\n    return \"outcome3\";\n  }\n};\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logs\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_parameters_demo\");\n\n  // Create a state machine\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{\"outcome4\"}, true);\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\"GETTING_PARAMETERS\",\n                yasmin_ros::GetParametersState::make_shared(\n                    yasmin_ros::GetParametersState::Parameters{\n                        {\"max_counter\", 3},\n                        {\"counter_str\", std::string(\"Counter\")},\n                    }),\n                {\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"FOO\"},\n                    {yasmin_ros::basic_outcomes::ABORT, \"outcome4\"},\n                });\n  sm-\u003eadd_state(\"FOO\", std::make_shared\u003cFooState\u003e(),\n                {\n                    {\"outcome1\", \"BAR\"},\n                    {\"outcome2\", \"outcome4\"},\n                });\n  sm-\u003eadd_state(\"BAR\", std::make_shared\u003cBarState\u003e(),\n                {\n                    {\"outcome3\", \"FOO\"},\n                });\n\n  // Publish state machine updates\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_PARAMETERS_DEMO\");\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Factory Demo (Plugins)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n\u003e **Note:** When mixing Python and C++ states in the same state machine, they can communicate through the blackboard, but only with primitive data types: `int`, `float`, `bool`, and `string`. Complex objects or ROS messages cannot be directly shared between Python and C++ states.\n\n```shell\nros2 run yasmin_demos factory_demo\n```\n\n```xml\n\u003cStateMachine outcomes=\"outcome4\"\u003e\n    \u003cState name=\"Foo\" type=\"py\" module=\"yasmin_demos.foo_state\" class=\"FooState\"\u003e\n        \u003cTransition from=\"outcome1\" to=\"Bar\"/\u003e\n        \u003cTransition from=\"outcome2\" to=\"outcome4\"/\u003e\n    \u003c/State\u003e\n    \u003cState name=\"Bar\" type=\"cpp\" class=\"yasmin_demos/BarState\"\u003e\n        \u003cTransition from=\"outcome3\" to=\"Foo\"/\u003e\n    \u003c/State\u003e\n\u003c/StateMachine\u003e\n```\n\n```cpp\n#include \u003ciostream\u003e\n#include \u003cmemory\u003e\n#include \u003cstring\u003e\n\n#include \"ament_index_cpp/get_package_share_directory.hpp\"\n#include \"rclcpp/rclcpp.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_factory/yasmin_factory.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set up ROS 2 loggers\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_factory_demo\");\n\n  // Create the factory in a scope\n  yasmin_factory::YasminFactory factory;\n\n  // Load state machine from XML file\n  std::string xml_file =\n      ament_index_cpp::get_package_share_directory(\"yasmin_demos\") +\n      \"/state_machines/demo_2.xml\";\n\n  // Create the state machine from the XML file\n  auto sm = factory.create_sm_from_file(xml_file);\n  sm-\u003eset_sigint_handler(true);\n\n  // Execute the state machine\n  try {\n    std::string outcome = (*sm.get())();\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  // Shutdown ROS 2\n  rclcpp::shutdown();\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n#### Nav2 Demo (Hierarchical FSM + ROS 2 Action)\n\n\u003cdetails\u003e\n\u003csummary\u003eClick to expand\u003c/summary\u003e\n\n```cpp\n#include \u003calgorithm\u003e\n#include \u003ciostream\u003e\n#include \u003cmap\u003e\n#include \u003cmemory\u003e\n#include \u003crandom\u003e\n#include \u003cstring\u003e\n#include \u003cvector\u003e\n\n#include \"geometry_msgs/msg/pose.hpp\"\n#include \"nav2_msgs/action/navigate_to_pose.hpp\"\n\n#include \"yasmin/blackboard.hpp\"\n#include \"yasmin/cb_state.hpp\"\n#include \"yasmin/logs.hpp\"\n#include \"yasmin/state_machine.hpp\"\n#include \"yasmin_ros/action_state.hpp\"\n#include \"yasmin_ros/basic_outcomes.hpp\"\n#include \"yasmin_ros/ros_logs.hpp\"\n#include \"yasmin_viewer/yasmin_viewer_pub.hpp\"\n\nusing std::placeholders::_1;\nusing std::placeholders::_2;\nusing NavigateToPose = nav2_msgs::action::NavigateToPose;\nusing Pose = geometry_msgs::msg::Pose;\n\n// Constants for state outcomes\nconst std::string HAS_NEXT = \"has_next\"; ///\u003c Indicates there are more waypoints\nconst std::string END = \"end\";           ///\u003c Indicates no more waypoints\n\n/**\n * @class Nav2State\n * @brief ActionState for navigating to a specified pose using ROS 2 Navigation.\n */\nclass Nav2State : public yasmin_ros::ActionState\u003cNavigateToPose\u003e {\npublic:\n  /**\n   * @brief Constructs a Nav2State object.\n   *\n   * Initializes the action state with the NavigateToPose action type,\n   * action name, and goal creation callback.\n   */\n  Nav2State()\n      : yasmin_ros::ActionState\u003cNavigateToPose\u003e(\n            \"/navigate_to_pose\",\n            std::bind(\u0026Nav2State::create_goal_handler, this, _1)) {}\n\n  /**\n   * @brief Creates a goal for navigation based on the current pose in the\n   * blackboard.\n   *\n   * @param blackboard Shared pointer to the blackboard instance holding current\n   * state data.\n   * @return NavigateToPose::Goal The constructed goal for the navigation\n   * action.\n   */\n  NavigateToPose::Goal create_goal_handler(\n      yasmin::Blackboard::SharedPtr blackboard) {\n    NavigateToPose::Goal goal;\n    goal.pose.pose = blackboard-\u003eget\u003cPose\u003e(\"pose\");\n    goal.pose.header.frame_id = \"map\"; // Set the reference frame to 'map'\n    return goal;\n  }\n};\n\n/**\n * @brief Initializes waypoints in the blackboard for navigation.\n *\n * @param blackboard Shared pointer to the blackboard instance to store\n * waypoints.\n * @return std::string Outcome indicating success (SUCCEED).\n */\nstd::string\ncreate_waypoints(yasmin::Blackboard::SharedPtr blackboard) {\n  std::map\u003cstd::string, std::vector\u003cdouble\u003e\u003e waypoints = {\n      {\"entrance\", {1.25, 6.30, -0.78, 0.67}},\n      {\"bathroom\", {4.89, 1.64, 0.0, 1.0}},\n      {\"livingroom\", {1.55, 4.03, -0.69, 0.72}},\n      {\"kitchen\", {3.79, 6.77, 0.99, 0.12}},\n      {\"bedroom\", {7.50, 4.89, 0.76, 0.65}}};\n  blackboard-\u003eset\u003cstd::map\u003cstd::string, std::vector\u003cdouble\u003e\u003e\u003e(\"waypoints\",\n                                                              waypoints);\n  return yasmin_ros::basic_outcomes::SUCCEED;\n}\n\n/**\n * @brief Selects a random set of waypoints from the available waypoints.\n *\n * @param blackboard Shared pointer to the blackboard instance to store random\n * waypoints.\n * @return std::string Outcome indicating success (SUCCEED).\n */\nstd::string take_random_waypoint(\n    yasmin::Blackboard::SharedPtr blackboard) {\n  auto waypoints =\n      blackboard-\u003eget\u003cstd::map\u003cstd::string, std::vector\u003cdouble\u003e\u003e\u003e(\"waypoints\");\n  int waypoints_num = blackboard-\u003eget\u003cint\u003e(\"waypoints_num\");\n\n  std::vector\u003cstd::string\u003e waypoint_names;\n  for (const auto \u0026pair : waypoints) {\n    waypoint_names.push_back(pair.first);\n  }\n\n  // Randomly select waypoints_num waypoints\n  std::random_device rd;\n  std::mt19937 g(rd());\n  std::shuffle(waypoint_names.begin(), waypoint_names.end(), g);\n  std::vector\u003cstd::string\u003e random_waypoints(\n      waypoint_names.begin(), waypoint_names.begin() + waypoints_num);\n\n  blackboard-\u003eset\u003cstd::vector\u003cstd::string\u003e\u003e(\"random_waypoints\",\n                                            random_waypoints);\n  return yasmin_ros::basic_outcomes::SUCCEED;\n}\n\n/**\n * @brief Retrieves the next waypoint from the list of random waypoints.\n *\n * Updates the blackboard with the pose of the next waypoint.\n *\n * @param blackboard Shared pointer to the blackboard instance holding current\n * state data.\n * @return std::string Outcome indicating whether there is a next waypoint\n * (HAS_NEXT) or if navigation is complete (END).\n */\nstd::string\nget_next_waypoint(yasmin::Blackboard::SharedPtr blackboard) {\n  auto random_waypoints =\n      blackboard-\u003eget\u003cstd::vector\u003cstd::string\u003e\u003e(\"random_waypoints\");\n  auto waypoints =\n      blackboard-\u003eget\u003cstd::map\u003cstd::string, std::vector\u003cdouble\u003e\u003e\u003e(\"waypoints\");\n\n  if (random_waypoints.empty()) {\n    return END;\n  }\n\n  std::string wp_name = random_waypoints.back();\n  random_waypoints.pop_back();\n  blackboard-\u003eset\u003cstd::vector\u003cstd::string\u003e\u003e(\"random_waypoints\",\n                                            random_waypoints);\n\n  auto wp = waypoints.at(wp_name);\n\n  Pose pose;\n  pose.position.x = wp[0];\n  pose.position.y = wp[1];\n  pose.orientation.z = wp[2];\n  pose.orientation.w = wp[3];\n\n  blackboard-\u003eset\u003cPose\u003e(\"pose\", pose);\n  blackboard-\u003eset\u003cstd::string\u003e(\"text\", \"I have reached waypoint \" + wp_name);\n\n  return HAS_NEXT;\n}\n\nint main(int argc, char *argv[]) {\n  // Initialize ROS 2\n  rclcpp::init(argc, argv);\n\n  // Set ROS 2 logs\n  yasmin_ros::set_ros_loggers();\n  YASMIN_LOG_INFO(\"yasmin_nav2_demo\");\n\n  // Create state machines\n  auto sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{yasmin_ros::basic_outcomes::SUCCEED,\n                                         yasmin_ros::basic_outcomes::ABORT,\n                                         yasmin_ros::basic_outcomes::CANCEL},\n      true);\n  auto nav_sm = yasmin::StateMachine::make_shared(\n      std::initializer_list\u003cstd::string\u003e{yasmin_ros::basic_outcomes::SUCCEED,\n                                         yasmin_ros::basic_outcomes::ABORT,\n                                         yasmin_ros::basic_outcomes::CANCEL});\n\n  // Add states to the state machine\n  sm-\u003eadd_state(\n      \"CREATING_WAYPOINTS\",\n      yasmin::CbState::make_shared(\n          std::initializer_list\u003cstd::string\u003e{\n              yasmin_ros::basic_outcomes::SUCCEED},\n          create_waypoints),\n      std::map\u003cstd::string, std::string\u003e{\n          {yasmin_ros::basic_outcomes::SUCCEED, \"TAKING_RANDOM_WAYPOINTS\"}});\n  sm-\u003eadd_state(\"TAKING_RANDOM_WAYPOINTS\",\n                yasmin::CbState::make_shared(\n                    std::initializer_list\u003cstd::string\u003e{\n                        yasmin_ros::basic_outcomes::SUCCEED},\n                    take_random_waypoint),\n                std::map\u003cstd::string, std::string\u003e{\n                    {yasmin_ros::basic_outcomes::SUCCEED, \"NAVIGATING\"}});\n\n  nav_sm-\u003eadd_state(\n      \"GETTING_NEXT_WAYPOINT\",\n      yasmin::CbState::make_shared(\n          std::initializer_list\u003cstd::string\u003e{END, HAS_NEXT}, get_next_waypoint),\n      std::map\u003cstd::string, std::string\u003e{\n          {END, yasmin_ros::basic_outcomes::SUCCEED},\n          {HAS_NEXT, \"NAVIGATING\"}});\n  nav_sm-\u003eadd_state(\n      \"NAVIGATING\", std::make_shared\u003cNav2State\u003e(),\n      std::map\u003cstd::string, std::string\u003e{\n          {yasmin_ros::basic_outcomes::SUCCEED, \"GETTING_NEXT_WAYPOINT\"},\n          {yasmin_ros::basic_outcomes::CANCEL,\n           yasmin_ros::basic_outcomes::CANCEL},\n          {yasmin_ros::basic_outcomes::ABORT,\n           yasmin_ros::basic_outcomes::ABORT}});\n\n  sm-\u003eadd_state(\n      \"NAVIGATING\", nav_sm,\n      std::map\u003cstd::string, std::string\u003e{{yasmin_ros::basic_outcomes::SUCCEED,\n                                          yasmin_ros::basic_outcomes::SUCCEED},\n                                         {yasmin_ros::basic_outcomes::CANCEL,\n                                          yasmin_ros::basic_outcomes::CANCEL},\n                                         {yasmin_ros::basic_outcomes::ABORT,\n                                          yasmin_ros::basic_outcomes::ABORT}});\n\n  // Publish FSM information for visualization\n  yasmin_viewer::YasminViewerPub yasmin_pub(sm, \"YASMIN_NAV2_DEMO\");\n\n  // Execute the state machine\n  auto blackboard = yasmin::Blackboard::make_shared();\n  blackboard-\u003eset\u003cint\u003e(\"waypoints_num\",\n                       2); // Set the number of waypoints to navigate\n\n  try {\n    std::string outcome = (*sm.get())(blackboard);\n    YASMIN_LOG_INFO(outcome.c_str());\n  } catch (const std::exception \u0026e) {\n    YASMIN_LOG_WARN(e.what());\n  }\n\n  rclcpp::shutdown();\n\n  return 0;\n}\n```\n\n\u003c/details\u003e\n\n## Cross‑Language ROS Interface Communication\n\nWhen mixing **Python** and **C++** states in the same YASMIN state\nmachine, the blackboard can be used to exchange data between them.\nHowever, due to language boundaries, only data types that can be safely\nserialized across runtimes should be used.\n\n### Supported Blackboard Types\n\nThe following types are guaranteed to work between Python and C++:\n\nType Description\n\n---\n\n- `int` Integer values\n- `float` Floating‑point values\n- `bool` Boolean values\n- `string` UTF‑8 text\n- `bytes` / `std::vector\u003cuint8_t\u003e` Binary data\n\n### Sharing ROS Interfaces Between Languages\n\nROS messages cannot be directly stored in the blackboard when\ncommunicating between Python and C++ states. Instead, they should be **serialized into raw bytes**.\n\nYASMIN provides helper utilities in:\n\n    yasmin_ros/interface_serialization.hpp\n\nThese utilities allow converting ROS interfaces to binary data and\nrestoring them later.\n\n### Example (C++)\n\n```cpp\n#include \"geometry_msgs/msg/pose.hpp\"\n#include \"yasmin_ros/interface_serialization.hpp\"\n\ngeometry_msgs::msg::Pose pose;\npose.position.x = 1.0;\npose.position.y = 2.0;\npose.position.z = 3.0;\n\nauto bytes = yasmin_ros::serialize_interface\u003cgeometry_msgs::msg::Pose\u003e(pose);\nblackboard-\u003eset\u003cstd::vector\u003cuint8_t\u003e\u003e(\"pose_bytes\", bytes);\n```\n\n### Example (Python)\n\n```python\nimport rclpy.serialization\nfrom geometry_msgs.msg import Pose\n\npose_bytes = blackboard[\"pose_bytes\"]\npose = rclpy.serialization.deserialize_message(pose_bytes, Pose)\n```\n\n## YASMIN Editor\n\nThe **YASMIN Editor** is a graphical user interface application for building YASMIN state machines using state plugins. It enables intuitive creation of state machines through drag-and-drop functionality, allowing you to:\n\n- Load Python and C++ states\n- Load XML state machines\n- Define transitions between states\n- Create outcomes\n- Visualize state machine structure\n\nState machines can be exported and saved in XML format for reuse and sharing.\n\n![YASMIN Editor Interface](./docs/editor.png)\n\n### Getting Started\n\n```shell\nros2 run yasmin_editor yasmin_editor\n```\n\n## YASMIN Viewer\n\nThe **YASMIN Viewer** provides a convenient way to monitor **YASMIN**'s Finite State Machines (FSM). It is built using **Flask** and **ReactJS** and includes a filter to focus on a single FSM at a time.\n\n![YASMIN Viewer](./docs/viewer.gif)\n\n### Getting Started\n\n```shell\nros2 run yasmin_viewer yasmin_viewer_node\n```\n\nOnce started, open http://localhost:5000/ in your browser to view your state machines.\n\n### Custom host and port\n\nYou can specify a custom host and port by using the following command:\n\n```shell\nros2 run yasmin_viewer yasmin_viewer_node --ros-args -p host:=127.0.0.1 -p port:=5032\n```\n\nAfter running the command, access your state machines at http://127.0.0.1:5032/.\n\n## Citations\n\n```bibtex\n@InProceedings{10.1007/978-3-031-21062-4_43,\nauthor=\"Gonz{\\'a}lez-Santamarta, Miguel {\\'A}.\nand Rodr{\\'i}guez-Lera, Francisco J.\nand Matell{\\'a}n-Olivera, Vicente\nand Fern{\\'a}ndez-Llamas, Camino\",\neditor=\"Tardioli, Danilo\nand Matell{\\'a}n, Vicente\nand Heredia, Guillermo\nand Silva, Manuel F.\nand Marques, Lino\",\ntitle=\"YASMIN: Yet Another State MachINe\",\nbooktitle=\"ROBOT2022: Fifth Iberian Robotics Conference\",\nyear=\"2023\",\npublisher=\"Springer International Publishing\",\naddress=\"Cham\",\npages=\"528--539\",\nabstract=\"State machines are a common mechanism for defining behaviors in robots where each behavior is based on identifiable stages. There are several libraries available for easing the implementation of state machines in ROS 1, however, the community was focused on SMACH or SMACC. Although these tools are still predominant, there are fewer alternatives for ROS 2. Besides, Behavior Trees are spreading fast, but there is a niche for using State Machines. Here, YASMIN is presented as yet another library specifically designed for ROS 2 for easing the design of robotic behaviors using state machines. It is available in C++ and Python, and provides some default states to speed up the development, in addition to a web viewer for monitoring the execution of the system and helping in the debugging.\",\nisbn=\"978-3-031-21062-4\"\n}\n```\n\n```bibtex\n@misc{yasmin,\n  doi = {10.48550/ARXIV.2205.13284},\n  url = {https://arxiv.org/abs/2205.13284},\n  author = {González-Santamarta, Miguel Ángel and Rodríguez-Lera, Francisco Javier and Llamas, Camino Fernández and Rico, Francisco Martín and Olivera, Vicente Matellán},\n  keywords = {Robotics (cs.RO), FOS: Computer and information sciences, FOS: Computer and information sciences},\n  title = {YASMIN: Yet Another State MachINe library for ROS 2},\n  publisher = {arXiv},\n  year = {2022},\n  copyright = {Creative Commons Attribution Non Commercial No Derivatives 4.0 International}\n}\n```\n","funding_links":[],"categories":["Software Packages"],"sub_categories":["Behavior Abstractions"],"project_url":"https://awesome.ecosyste.ms/api/v1/projects/github.com%2Fuleroboticsgroup%2Fyasmin","html_url":"https://awesome.ecosyste.ms/projects/github.com%2Fuleroboticsgroup%2Fyasmin","lists_url":"https://awesome.ecosyste.ms/api/v1/projects/github.com%2Fuleroboticsgroup%2Fyasmin/lists"}