Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Output data via socket to an external server and wait for reply on an input socket #74

Closed
agodemar opened this issue Jun 22, 2018 · 12 comments

Comments

@agodemar
Copy link
Contributor

agodemar commented Jun 22, 2018

Here I collect the main points of a previous discussion in a closed PR #72 .

The idea
The idea comes from this research article demonstrating how JSBSim can be used to run flight simulations in presence of a gust field pre-calculated with OpenFOAM. This is what I do:

  • The chosen aircraft model is flown through a volumetric CFD mesh. Each node in the grid owns three cartesian components of the local wind.
  • At each step of the FDM propagation, JSBSim sends the aircraft actual position (lat, lon, agl-altitude) to an external server application on an output TCP socket.
  • JSBSim blocks time propagation and waits for server reply.
  • The server reads and transforms the received geographic position in a triplet of Cartesian coordinates then accesses the velocity field associated to the mesh and calculates the local wind velocity by interpolation.
  • The server sends back on the same socket (in that case) the wind velocity.
  • JSBSim sets the new values of the properties: atmosphere/wind-north-fps, atmosphere/wind-east-fps, and atmosphere/wind-down-fps.
  • The FDM propagation continues.

Configuration
The O/I can be configured via the <output/> and <input/> tags as follows:

<!-- e.g. in file scripts/C1723.xml -->
<output name="localhost" type="SOCKET" port="1138" rate="20" file="unitconversions.xml">
  <property> position/lat-gc-deg </property>
  <property> position/long-gc-deg </property>
  <property apply="convert-ft-To-m" caption="position/h-agl-meters"> position/h-agl-ft </property>
</output>
<input type="SOCKET" port="1139" />

Strategy

The server application (OpenFOAM server) should do most of the work. By design, the OpenFOAM server has to manage asynchronously several running instances of JSBSim (e.g. hundreds, or thousands) providing them the wind data according to aircraft positions in the flow field.

On the initial iteration of the sim loop the JSBSim input socket doesn't have an incoming connection yet, it's still waiting for a connection. So it doesn't block in this case it simply returns.

Then at the end of the first iteration of the sim loop the output socket sends the initial aircraft state to the OpenFOAM server. The OpenFOAM server on receiving this initial incoming connection now knows the IP address of JSBSim and so it then creates a connection to the input socket (with some configured port number, i.e. 1139) that is waiting for connections. And it sends back it's first set of wind velocities.

So now on the next iteration of the sim loop the input socket will be connected and it will issue a blocking read to retrieve the OpenFOAM set commands for the wind velocities etc. and will process them and return allowing the sim loop to now continue in lock-step with the OpenFOAM server.

Issue
Glancing at the socket code a bit it looks like currently for the input socket case the socket passed to the accept() API is set to non-blocking, so it won't block waiting for a connection. The socket passed to the recv() API is also set to non-blocking after a successful accept().

For the OpenFOAM case/example it is not critical that the very first sim loop iteration needs data from the OpenFOAM server.

There may be some cases where it is critical that JSBSim has to receive the input data from the external server on the very first simulation loop iteration. To handle that case we could potentially have multiple flags for the input socket which specify blocking versus non-blocking for the accept() and the recv() calls independently.

So for the OpenFOAM example one would leave the accept() as non-blocking but set recv() blocking. For another server where the initial data is critical one would set both accept() and recv() to blocking. In which case JSBSim would start up but block until the external server connected and sent the first packet.

@agodemar
Copy link
Contributor Author

With an early test using this simplified server application, with the above <output/> and <input/> settings in the C1723.xml script, the I/O process seems to work.

No modifications of JSBSim code are required up to this point. I still have to sort out the blocking/non-blocking behaviour on the FGInputSocket side.

@bcoconni
Copy link
Member

@agodemar

No modifications of JSBSim code are required up to this point. I still have to sort out the blocking/non-blocking behaviour on the FGInputSocket side.

Excellent !

Regarding the handshaking, I think we can take advantage of JSBSim initialization process to initialize the communication with the server.

JSBSim initialization takes place in 2 phases:

First phase

FGFDMExec calls the InitModel() method of each "model". This includes FGInputSocket and FGOutputSocket. At this stage, no XML files has been read so the methods InitModel() basically initialize the models with default values, generally zeros and empty strings.

Second phase

FGFDMExec::RunIC() is called. At this stage all the XML files have been read and the models are set up. The interesting thing is that RunIC() actually calls Run() twice while the time propagation is suspended and the input and output elements are reset between the 2 runs. So in pseudo code it looks like (the detailed code can be viewed here)

SuspendIntegration();
Run();

Models[eInput]->InitModel();
Models[eOutput]->InitModel();

Run();
ResumeIntegration();

So even if the aircraft coordinates are not available to the server when data is polled from the input socket for the first time, the output socket will send the initial coordinates to the server at the end of this first Run().

Then the input and the output sockets are reset. This is mostly to hide that we have already processed a loop. For instance, the files are closed and re-opened thereby deleting (hiding) the output of the first initialization pass.

Then Run() is called for the second time, but this time, the OpenFOAM server will have the correct coordinates so the data sent to JSBSim by the input socket will be correct and the rest of the time step execution will account for the correct wind conditions.

Since all of this took place without time propagation, JSBSim is initialized at the end of the second Run() while the time is still t=0.

So how this information is any relevant to the problem ?

The idea is that when InitModel() is called we can have different behaviors depending on whether the socket is already set up or not.

  • If the socket is not set up, a non blocking socket is used.
  • If the socket is already set up, the current socket is replaced by a blocking socket.

My suggestion would then be to create a new class that inherits FGInputSocket and which method InitModel() would be overloaded to execute a sequence similar to the above.

@tridge
Copy link

tridge commented Jun 22, 2018

Possibly relevant to this discussion is a change I made for using JSBSim as a software-in-the-loop simulator for ArduPilot many years ago. The patch is here:
tridge/jsbsim@9a68300
The approach that used was to add a "step" command, which would both step by one loop, and enable stepping mode if not already enabled. That way you don't need special config setups.
This patch is against an ancient version of JSBSim though, and JSBSim is no longer the primary SITL backend we use for ArduPilot (we have some simpler built-in simulator models that are more commonly used).
Recent a PR (ArduPilot/ardupilot#8710) was opened by @WillemEerland to bring ArduPilot up to date with the latest JSBSim, and the only missing piece is support for lock-step scheduling. It really is essential for autopilot testing as without it the EKF state estimator gets unhappy very quickly as its sensor data is not kinematically consistent due to timing delays on the host computer. It is also very useful to be able to step through the simulation in a debugger without changing the physics.
My apologies for not submitting this patch as a PR back when I first wrote it. I thought it was a bit of a specialized hack for ArduPilot.

@agodemar
Copy link
Contributor Author

@bcoconni

My suggestion would then be to create a new class that inherits FGInputSocket and which method InitModel() would be overloaded to execute a sequence similar to the above.

Would you please post here a skeleton of the class you have in mind?

@bcoconni
Copy link
Member

@tridge

the only missing piece is support for lock-step scheduling

This seems very similar to the already existing command iterate which provides a similar functionality with the additional feature that you can provide the number of steps to be run before holding.

However there is this method FGFDMExec::WaitInput that has no equivalent in the iterate command. What is its purpose ?

@bcoconni
Copy link
Member

@agodemar

Would you please post here a skeleton of the class you have in mind?

Sure, will do if you can wait till tomorrow (it's late now and I have to go 💤 😴 )

@seanmcleod
Copy link
Member

@bcoconni

However there is this method FGFDMExec::WaitInput that has no equivalent in the iterate command. What is its purpose ?

It blocks waiting for socket input using select(), so it only returns once there is data available to be read from the input socket. So it 'holds/blocks' the sim from executing another time step until Ardupilot writes to the socket again.

Which is why I mentioned to @WillemEerland that it looks very similar to @agodemar's suggestion for lock step simulation with an external process.

@bcoconni
Copy link
Member

@agodemar

Would you please post here a skeleton of the class you have in mind?

After some investigations, the solution might not be as complicated as I initially described.

My suggestion is to create a new method FGfdmSocket::WaitForReply() with the code you submitted in the PR #72

string FGfdmSocket::WaitForReply(void)
{
  if (sckt > 0) {
    char in_buf[4096]; // assume this is a sufficiently large buffer
    int bytes_read = 0;
    bytes_read = recv(sckt, in_buf, sizeof in_buf, 0); // MSG_PEEK -> check but does not read
    data.append(in_buf, bytes_read);
  }
  return data;
}

then FGInputSocket could selectively call FGfdmSocket::Receive() or FGfdmSocket::WaitForReply() depending on whether action="WAIT_SOCKET_REPLY" has been set in the <input> element.

@@ -119,7 +119,10 @@ void FGInputSocket::Read(bool Holding)
   if (socket == 0) return;
   if (!socket->GetConnectStatus()) return;
 
-  data = socket->Receive(); // get socket transmission if present
+  if (waitForSocketReply)
+    data = socket->WaitForReply(); // block until a transmission is received
+  else
+    data = socket->Receive(); // get socket transmission if present
 
   if (data.size() > 0) {
     // parse lines

This socket will block at the first iteration. Not sure, if this is a problem ?

Glancing at the socket code a bit it looks like currently for the input socket case the socket passed to the accept() API is set to non-blocking, so it won't block waiting for a connection. The socket passed to the recv() API is also set to non-blocking after a successful accept().

AFAICT this is only applicable to UDP sockets and you are using a TCP socket (no protocol is supplied in <input>)

@seanmcleod
Copy link
Member

seanmcleod commented Jun 26, 2018

Minor comment - let's not call the action "WAIT_SOCKET_REPLY", a user may want to have a blocking input socket independently of whether there is an output socket sending it information first etc. For example say I have a network based joystick or some other input system that I want to retrieve input for on a per sim time step before the sim continues. So I'd suggest rather something like action="BLOCKING_INPUT".

I'd suggest code along the following lines:

void FGfdmSocket::WaitUntilReadable(void)
{
  fd_set fds; 
  FD_ZERO(&fds);
  FD_SET(sckt_in, &fds); 
  select(sckt_in+1, &fds, NULL, NULL, NULL); 
}

In other words use select like @tridge did in his Wait() implementation.

And then:

@@ -119,7 +119,10 @@ void FGInputSocket::Read(bool Holding)
   if (socket == 0) return;
   if (!socket->GetConnectStatus()) return;
 
-  data = socket->Receive(); // get socket transmission if present
+  if (blockingInput)
+    socket->WaitUntilReadable(); // block until a transmission is received
+  data = socket->Receive(); // read data
 
   if (data.size() > 0) {
     // parse lines

bcoconni added a commit to bcoconni/jsbsim that referenced this issue Jun 30, 2018
@bcoconni
Copy link
Member

I implemented some code in the PR #81 for this feature following the discussions we had above.
Please review and send your comments.

agodemar pushed a commit that referenced this issue Jul 4, 2018
@bcoconni I merge this PR in order to test it on my fork.

* Skeleton for #74
* Make the attribute "action" case insensitive.
@bcoconni
Copy link
Member

bcoconni commented Sep 2, 2018

@agodemar I understood that this issue has been fixed since PR #109 has been merged.

Can this issue be closed ?

@agodemar
Copy link
Contributor Author

agodemar commented Sep 2, 2018

Yes, fixed. I will close it.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

4 participants