Simple Writer/Reader example
The main purpose of this tutorial is to create two periodic components: a writer and a reader. The first one writes data in a resource, the second one reads the data.
The corresponding files can be found in the mauve_tutorials respository.
Writer Component
The writer component periodicaly write an increasing int value on its output port.
Writer Shell
In mauve runtime ports are contained in the shell of the component. A port is created in the shell using the mk_port method. This method takes the name of the port in parameted and returns a reference to the port.
In our example, the shell of the writer component only contains an ouput port of type int.
struct WriterShell: public Shell {
// Create the ouput port of type int and named "out"
WritePort<int> & output = mk_port<WritePort<int>>("output");
};
Writer Core
The core of the writer component contains the code and the internal data of the component. In this example, the only internal data is a counter. The update() method of the core writes the counter to output port of the shell and increases it. We ca notice that the core can access to its shell using the method shell() and consequently can use the shell ports.
struct WriterCore: public Core<WriterShell> {
// Override the configure hook by setting the initial value of "count"
bool configure_hook() override {
count = 1;
return true;
}
void update() {
// Display current count value
std::cout << this->type_name() << "> count = " << count << std::endl;
// Write count to the shell port "output"
shell().output.write(count++);
}
private:
int count;
};
Writer Finite State Machine
The writer finite state machine simply executes the update() method of the core each 1 sec.
struct WriterFSM: public FiniteStateMachine<WriterShell, WriterCore> {
// Create the Execution state: run the update method of the core
ExecState<WriterCore> & U = mk_execution("Update", &WriterCore::update);
// Create the synchronization state: 1 sec
SynchroState<WriterCore> & W = mk_synchronization("Wait", sec_to_ns(1));
bool configure_hook() override {
set_initial(U); // set the initial state to Update
set_next(U, W); // Wait after Update
set_next(W, U); // Update after Wait
return true;
}
};
Reader Component
The reader component objective is to read periodicaly a share data of type int and display its value.
Reader Shell
The shell of the reader component only contains a ReadPort of type int. We can notice that, contrary to the WritePort the ReadPort has default value. The default value is used when the component reads a not connected port.
struct ReaderShell: public Shell {
// Create the input port of type int and named "input"
ReadPort<int> & input = mk_port<ReadPort<int>>("input", -1);
};
Reader Core
The reader core simply read the data and displya its value.
struct ReaderCore: public Core<ReaderShell> {
void update() {
// Read the input Port
int count = shell().input.read();
// Display current count value
std::cout << this->type_name() << "> count = " << count << std::endl;
}
};
Reader Finite State Machine
The reader finite state machine simply executes the update() method of the core each 1 sec.
struct ReaderFSM: public FiniteStateMachine<ReaderShell, ReaderCore> {
// Create the Execution state: run the update method of the core
ExecState<ReaderCore> & U = mk_execution("Update", &ReaderCore::update);
// Create the synchronization state: 1 sec
SynchroState<ReaderCore> & W = mk_synchronization("Wait", sec_to_ns(1));
bool configure_hook() override {
set_initial(U); // set the initial state to Update
set_next(U, W); // Wait after Update
set_next(W, U); // Update after Wait
return true;
}
};
Architecture
The architecture is made of 2 components and a resource. The output port of the writer and the input port of the reader are connected to the resource. In this example we use a SharedData resource. This resource main purpose is to exchange a single data of any type. Notice that the SharedData has an initial value.
struct WriterReaderArchi: public Architecture {
// Create the Writer component
Component<WriterShell, WriterCore, WriterFSM> & writer = mk_component<WriterShell, WriterCore, WriterFSM>("writer");
// Create the Reader component
Component<ReaderShell, ReaderCore, ReaderFSM> & reader = mk_component<ReaderShell, ReaderCore, ReaderFSM>("reader");
// Create Shared Data Resource
SharedData<int> & data = mk_resource<SharedData<int>>("data", 0);
...
};
The configure_hook() of the architecture first connect the components ports to the shared data. Then it configures the resource and the components. This sequence is important because once a component (i.e. a resource) is configured it cannot be connected or disconnected.
Then, the affinity of the components is set to be on the same cpu. Finaly the real-time priority of the components is set. In this example the writer is more prioritary than the reader.
bool configure_hook() override {
// Connect the output port to the resource
writer.shell().output.connect(data.interface().write);
// Connect the input port to the resource
reader.shell().input.connect(data.interface().read_value);
// Configure the resource
data.configure();
// Configure the writer
writer.configure();
// Configure the reader
reader.configure();
// Set the affinity of the components
// -> Both on the same processor
writer.set_cpu(0);
reader.set_cpu(0);
// Set the priority of the components
// writer is more prioritary than the reader
writer.set_priority(11);
reader.set_priority(10);
return true;
}
Deployment
int main(int argc, char const *argv[]) {
// Create the architecture
WriterReaderArchi architecture;
// Create a deployer for the architecture
AbstractDeployer* deployer = mk_abstract_deployer(&architecture);
// Configure the architecture
architecture.configure();
// Create the component task
deployer->create_tasks();
// Activate the component task
deployer->activate();
// Start the deployer and the component task
deployer->start();
// Deployer is running until C-C
deployer->loop();
// Stop the deployer and the component task
deployer->stop();
return 0;
}
Real-Time Execution
The real-time execution is the following one:
$ ./devel/lib/writer_reader/writer_reader
WriterCore> count = 1
ReaderCore> count = 1
WriterCore> count = 2
ReaderCore> count = 2
WriterCore> count = 3
ReaderCore> count = 3
WriterCore> count = 4
ReaderCore> count = 4
WriterCore> count = 5
ReaderCore> count = 5
...
Going further
Real time execution and SharedData initial value
Lets change the priorties of the components; the reader is more prioritary than the writer.
bool configure_hook() override {
...
// Set the priority of the components
// writer is more prioritary than the reader
writer.set_priority(10);
reader.set_priority(11);
...
}
The execution is the following one:
$ ./devel/lib/writer_reader/writer_reader
ReaderCore> count = 0
WriterCore> count = 1
ReaderCore> count = 1
WriterCore> count = 2
ReaderCore> count = 2
WriterCore> count = 3
ReaderCore> count = 3
WriterCore> count = 4
ReaderCore> count = 4
WriterCore> count = 5
ReaderCore> count = 5
...
As the writer and the reader components are launched exactly at the same instant and because the priority of the reader is greater the reader starts its execution before the writer. Thus its first execution reads the initial value of the SharedData.
Shared Data default value
Lets changed the architure configure_hook() by removing the reader connection to the SharedData:
bool configure_hook() override {
// Connect the output port to the resource
writer.shell().output.connect(data.interface().write);
// Connect the input port to the resource
// reader.shell().input.connect(data.interface().read_value);
..
}
The execution is the following one:
$ ./devel/lib/writer_reader/writer_reader
WriterCore> count = 1
ReaderCore> count = -1
WriterCore> count = 2
ReaderCore> count = -1
WriterCore> count = 3
ReaderCore> count = -1
WriterCore> count = 4
ReaderCore> count = -1
WriterCore> count = 5
ReaderCore> count = -1
...
In this example, the reader input port is not connected. Consequently its core continiously read the default value of the port.