multi-output single input connections?

It might be that I did not search properly, but I cannot find in the docs / on the mailing list what is the current status of the connection pattern with multiple OutputPorts and a single InputPort. I know it has been discussed during the dataflow overhaul, but what is the result? Is it allowed or not? And if allowed, are there pitfalls to be expected? I am specifically interested in the case that the InputPort is an event port.

Thanks in advance, Theo.

multi-output single input connections?

Hello Theo,

On Wednesday 24 August 2011 14:37:29 t [dot] j [dot] a [dot] devries [..] ... wrote:
> It might be that I did not search properly, but I cannot find in the docs /
> on the mailing list what is the current status of the connection pattern
> with multiple OutputPorts and a single InputPort. I know it has been
> discussed during the dataflow overhaul, but what is the result? Is it
> allowed or not? And if allowed, are there pitfalls to be expected? I am
> specifically interested in the case that the InputPort is an event port.

In one of our application we have exactly the same setting as you: multiple
outputports connected to a since inputport where the inputport is an event
port.

The first thing you should know about this setting is that for every input-
outputport combination a separte connection is created. So you can decide the
connectionpolicy for every single connection.

After some private discussion with Peter Soetens we also had some details
about the actual behavior. I will tell below the thing that I rememberered and
I hope that Peter corrects me my explanation contains some mistakes.

When multiple outputports are connected to the same inputport, the inputport
will cycle over the different connections when reading. As long as the current
connection he is reading from contains new data, the inputport will keep on
reading from this connection. As soon as there is no new data on the
connection, the inputport will go to the next connection and check if this one
contains new data. Again as long as it contains new data it reads from it
otherwise it will go to the next connection.
If in one cycle through all the connections, there was no new data on any of
the connections, the inputport will got to the OldData state.

Then, when we were testing our connection we discovered a bug in the
implementation. From time to time we missed a sample, which was being caused
by all connections being cleared if a loop through all the connection did not
show new data. Therefore, if a new sample arrived on a connection after being
checked but before the loop over all the connections was finished, the sample
was lost.
Peter was so kind to make a patch within half an hour after we found the
mistake and the patch is already applied to master.

Hope this explanation helps you.

Tinne

multi-output single input connections?

On Sun, 4 Sep 2011, Tinne De Laet wrote:

>
> Hello Theo,
>
>
> On Wednesday 24 August 2011 14:37:29 t [dot] j [dot] a [dot] devries [..] ... wrote:
> > It might be that I did not search properly, but I cannot find in the docs /
> > on the mailing list what is the current status of the connection pattern
> > with multiple OutputPorts and a single InputPort. I know it has been
> > discussed during the dataflow overhaul, but what is the result? Is it
> > allowed or not? And if allowed, are there pitfalls to be expected? I am
> > specifically interested in the case that the InputPort is an event port.
>
> In one of our application we have exactly the same setting as you: multiple
> outputports connected to a since inputport where the inputport is an event
> port.
>
> The first thing you should know about this setting is that for every
> input-outputport combination a separte connection is created. So you can
> decide the connectionpolicy for every single connection.
>
> After some private discussion with Peter Soetens we also had some details
> about the actual behavior. I will tell below the thing that I rememberered and
> I hope that Peter corrects me my explanation contains some mistakes.
>
> When multiple outputports are connected to the same inputport, the inputport
> will cycle over the different connections when reading. As long as the current
> connection he is reading from contains new data, the inputport will keep on
> reading from this connection. As soon as there is no new data on the
> connection, the inputport will go to the next connection and check if this one
> contains new data. Again as long as it contains new data it reads from it
> otherwise it will go to the next connection.

This default behaviour is motivated by (i) all new available data is read
in each activation of the inputting component, and (ii) if this is not what
you want, you should either interweave a component that implements your
policy, or reconfigure the Communication components that get the data to
the input port. We think any other policy would force the implementation of
the inputting component to know too much about the architecture of the rest
of the system it is connected to.

> If in one cycle through all the connections, there was no new data on any of
> the connections, the inputport will got to the OldData state.

> Then, when we were testing our connection we discovered a bug in the
> implementation. From time to time we missed a sample, which was being caused
> by all connections being cleared if a loop through all the connection did not
> show new data. Therefore, if a new sample arrived on a connection after being
> checked but before the loop over all the connections was finished, the sample
> was lost.
>
> Peter was so kind to make a patch within half an hour after we found the
> mistake and the patch is already applied to master.

And I hope the patch does only one thing, and that is to remove the
clearing?

> Hope this explanation helps you.
>
> Tinne

Herman

multi-output single input connections?

On Sunday 04 September 2011 17:41:02 Herman Bruyninckx wrote:
> On Sun, 4 Sep 2011, Tinne De Laet wrote:
> > Hello Theo,
> >
> > On Wednesday 24 August 2011 14:37:29 t [dot] j [dot] a [dot] devries [..] ... wrote:
> > > It might be that I did not search properly, but I cannot find in the
> > > docs / on the mailing list what is the current status of the
> > > connection pattern with multiple OutputPorts and a single InputPort. I
> > > know it has been discussed during the dataflow overhaul, but what is
> > > the result? Is it allowed or not? And if allowed, are there pitfalls
> > > to be expected? I am specifically interested in the case that the
> > > InputPort is an event port.
> >
> > In one of our application we have exactly the same setting as you:
> > multiple outputports connected to a since inputport where the inputport
> > is an event port.
> >
> > The first thing you should know about this setting is that for every
> > input-outputport combination a separte connection is created. So you can
> > decide the connectionpolicy for every single connection.
> >
> > After some private discussion with Peter Soetens we also had some details
> > about the actual behavior. I will tell below the thing that I
> > rememberered and I hope that Peter corrects me my explanation contains
> > some mistakes.
> >
> > When multiple outputports are connected to the same inputport, the
> > inputport will cycle over the different connections when reading. As
> > long as the current connection he is reading from contains new data, the
> > inputport will keep on reading from this connection. As soon as there is
> > no new data on the connection, the inputport will go to the next
> > connection and check if this one contains new data. Again as long as it
> > contains new data it reads from it otherwise it will go to the next
> > connection.
>
> This default behaviour is motivated by (i) all new available data is read
> in each activation of the inputting component, and (ii) if this is not what
> you want, you should either interweave a component that implements your
> policy, or reconfigure the Communication components that get the data to
> the input port. We think any other policy would force the implementation of
> the inputting component to know too much about the architecture of the rest
> of the system it is connected to.
>
> > If in one cycle through all the connections, there was no new data on any
> > of the connections, the inputport will got to the OldData state.

That's all correct.

> >
> > Then, when we were testing our connection we discovered a bug in the
> > implementation. From time to time we missed a sample, which was being
> > caused by all connections being cleared if a loop through all the
> > connection did not show new data. Therefore, if a new sample arrived on
> > a connection after being checked but before the loop over all the
> > connections was finished, the sample was lost.
> >
> > Peter was so kind to make a patch within half an hour after we found the
> > mistake and the patch is already applied to master.
>
> And I hope the patch does only one thing, and that is to remove the
> clearing?

Yes. This however caused another piece of code in RTT to fail (as reported by
the unit tests) which then also required fixing in the same patch.

Peter