Program Listing for File state_machine.hpp

Return to documentation for file (include/yasmin/state_machine.hpp)

// Copyright (C) 2023 Miguel Ángel González Santamarta
//
// This program is free software: you can redistribute it and/or modify
// it under the terms of the GNU General Public License as published by
// the Free Software Foundation, either version 3 of the License, or
// (at your option) any later version.
//
// This program is distributed in the hope that it will be useful,
// but WITHOUT ANY WARRANTY; without even the implied warranty of
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
// GNU General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// along with this program.  If not, see <https://www.gnu.org/licenses/>.

#ifndef YASMIN__STATE_MACHINE_HPP_
#define YASMIN__STATE_MACHINE_HPP_

#include <atomic>
#include <condition_variable>
#include <functional>
#include <mutex>
#include <string>
#include <vector>

#include "yasmin/blackboard.hpp"
#include "yasmin/state.hpp"

namespace yasmin {

class StateMachine : public State {

public:
  using StartCallbackType =
      std::function<void(Blackboard::SharedPtr, const std::string &)>;
  using TransitionCallbackType =
      std::function<void(Blackboard::SharedPtr, const std::string &,
                         const std::string &, const std::string &)>;
  using EndCallbackType =
      std::function<void(Blackboard::SharedPtr, const std::string &)>;

  YASMIN_PTR_ALIASES(StateMachine)


  StateMachine(const Outcomes &outcomes, bool handle_sigint = false);

  StateMachine(const std::string &name, const Outcomes &outcomes,
               bool handle_sigint = false);

  ~StateMachine();

  void add_state(const std::string &name, State::SharedPtr state,
                 const Transitions &transitions = {},
                 const Remappings &remappings = {});

  void set_name(const std::string &name) { this->name = name; }

  const std::string &get_name() const noexcept { return this->name; }

  void set_start_state(const std::string &state_name);

  std::string const &get_start_state() const noexcept;

  StateMap const &get_states() const noexcept;

  TransitionsMap const &get_transitions() const noexcept;

  std::string const &get_current_state() const;

  void add_start_cb(StartCallbackType cb);

  void add_transition_cb(TransitionCallbackType cb);

  void add_end_cb(EndCallbackType cb);

  void validate(bool strict_mode = false);

  std::string execute(Blackboard::SharedPtr blackboard) override;

  std::string execute();

  std::string operator()();

  // Use the base class operator()
  using State::operator();

  void cancel_state() override;

  void set_sigint_handler(bool handle = true);

  std::string to_string() const override;

private:
  // Name of the state machine (used if this is the root state machine)
  std::string name;

  StateMap states;
  TransitionsMap transitions;
  RemappingsMap remappings;

  std::string start_state;
  std::string current_state;
  std::unique_ptr<std::mutex> current_state_mutex;
  std::condition_variable current_state_cond;

  std::atomic_bool validated{false};

  std::vector<StartCallbackType> start_cbs;
  std::vector<TransitionCallbackType> transition_cbs;
  std::vector<EndCallbackType> end_cbs;

  void set_current_state(const std::string &state_name);

  void call_start_cbs(Blackboard::SharedPtr blackboard,
                      const std::string &start_state);

  void call_transition_cbs(Blackboard::SharedPtr blackboard,
                           const std::string &from_state,
                           const std::string &to_state,
                           const std::string &outcome);

  void call_end_cbs(Blackboard::SharedPtr blackboard,
                    const std::string &outcome);
};

} // namespace yasmin

#endif // YASMIN__STATE_MACHINE_HPP_