Skip to content
Open
Show file tree
Hide file tree
Changes from 5 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions alica_engine/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -37,9 +37,11 @@ add_library(${PROJECT_NAME} SHARED
src/engine/BasicUtilityFunction.cpp
src/engine/ConfigChangeListener.cpp
src/engine/DefaultUtilityFunction.cpp
src/engine/Executor.cpp
src/engine/FileSystem.cpp
src/engine/IAlicaCommunication.cpp
src/engine/IRoleAssignment.cpp
src/engine/IExecutor.cpp
src/engine/PlanBase.cpp
src/engine/PlanRepository.cpp
src/engine/RuleBook.cpp
Expand Down
3 changes: 2 additions & 1 deletion alica_engine/include/engine/AlicaContext.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
#include "engine/IBehaviourCreator.h"
#include "engine/IConditionCreator.h"
#include "engine/IConstraintCreator.h"
#include "engine/IExecutor.h"
#include "engine/IPlanCreator.h"
#include "engine/ITransitionConditionCreator.h"
#include "engine/IUtilityCreator.h"
Expand Down Expand Up @@ -245,7 +246,7 @@ class AlicaContext
*
* @see AlicaCreators
*/
int init(AlicaCreators&& creatorCtx, bool delayStart = false);
int init(AlicaCreators&& creatorCtx, bool delayStart = false, const std::shared_ptr<IExecutor>& executor = nullptr);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why not use a setter for it like with the other injected dependencies?


/**
* Terminate alica framework and related modules. This function must be called for safe termination before
Expand Down
4 changes: 3 additions & 1 deletion alica_engine/include/engine/AlicaEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -43,10 +43,11 @@ class AlicaEngine
~AlicaEngine();

// State modifiers:
bool init(AlicaCreators&& creatorCtx);
bool init(AlicaCreators&& creatorCtx, const std::shared_ptr<IExecutor>& executor);
void start();
void terminate();
void stepNotify();
void step();

// Parameter Access:
// bool getStepEngine() const;
Expand Down Expand Up @@ -134,6 +135,7 @@ class AlicaEngine
ExpressionHandler _expressionHandler;
AuthorityManager _auth;
DefaultTransitionConditionCreator _defaultTransitionConditionCreator;
std::shared_ptr<IExecutor> _executor;
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

S: Can be removed, should be enough to store in in AlicaContext like other injected dependencies


/**
* TODO: Make VariableSyncModule a stack variable.
Expand Down
37 changes: 37 additions & 0 deletions alica_engine/include/engine/Executor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#pragma once
#include "engine/IExecutor.h"
#include <atomic>
#include <memory>
#include <thread>

namespace alica
{

class AsyncExecutor : public IExecutor
{

public:
AsyncExecutor(){};
~AsyncExecutor() override { stop(); };

void start() override;
void stop() override;
void run() override;

private:
std::unique_ptr<std::thread> _thread;
std::atomic<bool> _running{false};
};

class DrivenExecutor : public IExecutor
{
public:
DrivenExecutor(){};
~DrivenExecutor() override = default;

void start() override{};
void stop() override{};
void run() override;
};

} // namespace alica
18 changes: 18 additions & 0 deletions alica_engine/include/engine/IExecutor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#pragma once
#include <functional>

namespace alica
{
class IExecutor
{
public:
virtual ~IExecutor() = default;
virtual void start() = 0;
virtual void stop() = 0;
virtual void run() = 0; // only for driven executor
Copy link
Collaborator

@bjoernschroeder bjoernschroeder Oct 8, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

F: Its also used by AsyncExecutor (but not supposed to be used externally, so maybe you should move current run implementation of AsyncExecutor to another private method?)

void attachRunCb(std::function<void()>&& runCb);

protected:
std::function<void()> _run_cb = nullptr;
};
} // namespace alica
9 changes: 5 additions & 4 deletions alica_engine/include/engine/PlanBase.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
#pragma once

#include "engine/AlicaClock.h"
#include "engine/IExecutor.h"
#include "engine/RuleBook.h"
#include "engine/RunningPlan.h"
#include "engine/RuntimeBehaviourFactory.h"
Expand All @@ -12,6 +13,7 @@
#include <math.h>
#include <memory>
#include <mutex>
#include <optional>
#include <queue>
#include <stdio.h>
#include <thread>
Expand Down Expand Up @@ -57,7 +59,8 @@ class PlanBase
const AlicaTime getLoopInterval() const;
void setLoopInterval(AlicaTime loopInterval);
void stop();
void start(const Plan* masterPlan);
void start(const Plan* masterPlan, const std::shared_ptr<IExecutor>& executor);
void run(const Plan* masterPlan);
void addFastPathEvent(RunningPlan* p);
bool isWaiting() const { return _isWaiting; }

Expand All @@ -75,8 +78,6 @@ class PlanBase
private:
static constexpr const char* LOGNAME = "PlanBase";

void run(const Plan* masterPlan);

// Owning container of running plans (replace with uniqueptrs once possible)
std::vector<std::shared_ptr<RunningPlan>> _runningPlans;

Expand Down Expand Up @@ -104,8 +105,8 @@ class PlanBase

const RunningPlan* _deepestNode;

std::unique_ptr<std::thread> _mainThread;
std::unique_ptr<AlicaEngineInfo> _statusMessage;
std::shared_ptr<IExecutor> _executor;

AlicaTime _loopTime;
AlicaTime _lastSendTime;
Expand Down
4 changes: 2 additions & 2 deletions alica_engine/src/engine/AlicaContext.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ int AlicaContext::init(AlicaCreators& creatorCtx)
return init(std::move(creators));
}

int AlicaContext::init(AlicaCreators&& creatorCtx, bool delayStart)
int AlicaContext::init(AlicaCreators&& creatorCtx, bool delayStart, const std::shared_ptr<IExecutor>& executor)
{
if (_initialized) {
Logging::logWarn(LOGNAME) << "Context already initialized.";
Expand All @@ -94,7 +94,7 @@ int AlicaContext::init(AlicaCreators&& creatorCtx, bool delayStart)

_communicator->startCommunication();

if (_engine->init(std::move(creatorCtx))) {
if (_engine->init(std::move(creatorCtx), executor)) {
LockedBlackboardRW gbb(*_globalBlackboard);
gbb.set("agentName", _engine->getLocalAgentName());
gbb.set("agentId", _engine->getTeamManager().getLocalAgentID());
Expand Down
8 changes: 6 additions & 2 deletions alica_engine/src/engine/AlicaEngine.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
#include "engine/AlicaEngine.h"

#include "engine/Executor.h"
#include "engine/IRoleAssignment.h"
#include "engine/StaticRoleAssignment.h"
#include "engine/Types.h"
Expand Down Expand Up @@ -81,14 +82,17 @@ void AlicaEngine::reload(const YAML::Node& config)
* Initialise the engine
* @return bool true if everything worked false otherwise
*/
bool AlicaEngine::init(AlicaCreators&& creatorCtx)
bool AlicaEngine::init(AlicaCreators&& creatorCtx, const std::shared_ptr<IExecutor>& executor)
{
if (_initialized) {
Logging::logWarn(LOGNAME) << "Already initialized.";
return true; // todo false?
}

_executor = executor ? executor : std::make_shared<AsyncExecutor>();

_planBase.init(std::move(creatorCtx.behaviourCreator), std::move(creatorCtx.planCreator));
_executor->attachRunCb(std::bind(&PlanBase::run, &_planBase, _masterPlan));

_roleAssignment->init();

Expand All @@ -109,7 +113,7 @@ bool AlicaEngine::init(AlicaCreators&& creatorCtx)
void AlicaEngine::start()
{
// TODO: Removing this api need major refactoring of unit tests.
_planBase.start(_masterPlan);
_planBase.start(_masterPlan, _executor);
Logging::logInfo(LOGNAME) << "Engine started!";
}
/**
Expand Down
37 changes: 37 additions & 0 deletions alica_engine/src/engine/Executor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
#include "engine/Executor.h"
#include <cassert>

namespace alica
{

void AsyncExecutor::start()
{
assert(_run_cb);
_running = true;
_thread = std::make_unique<std::thread>(&AsyncExecutor::run, this);
}

void AsyncExecutor::stop()
{
_running = false;
if (_thread) {
_thread->join();
_thread.reset();
}
}

void AsyncExecutor::run()
{
assert(_run_cb);
while (_running) {
_run_cb();
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wont this call PlanBase::run() without respecting any configured frequencies and cause 100% cpu load?

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think it basically just moved the while loop here. Unless the previous implementation was also suffering the same issue, I don't think the loop here will cause a 100% CPU load?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ahh yes, PlanBase run still has a sleep to enforce frequency. But this also causes the sleep to keep a max frequency on the DrivenExecutor, which might be an undesired side effect. It seems only using stepEngine will get us around the sleep.

Copy link
Author

@marcus65001 marcus65001 Oct 9, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think these are more of a configuration issue? Maybe we shouldn't set stepEngine=true when we have configured the alica context to use DrivenExecutor.

}
}

void DrivenExecutor::run()
{
assert(_run_cb);
_run_cb();
}

} // namespace alica
11 changes: 11 additions & 0 deletions alica_engine/src/engine/IExecutor.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#include "engine/IExecutor.h"

namespace alica
{

void IExecutor::attachRunCb(std::function<void()>&& runCb)
{
_run_cb = std::move(runCb);
}

} // namespace alica
Loading
Loading