Comments (12)
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.
from jsbsim.
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
from jsbsim.
I implemented some code in the PR #81 for this feature following the discussions we had above.
Please review and send your comments.
from jsbsim.
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.
from jsbsim.
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.
from jsbsim.
My suggestion would then be to create a new class that inherits
FGInputSocket
and which methodInitModel()
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?
from jsbsim.
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 ?
from jsbsim.
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 💤 😴 )
from jsbsim.
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.
from jsbsim.
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>
)
from jsbsim.
@agodemar I understood that this issue has been fixed since PR #109 has been merged.
Can this issue be closed ?
from jsbsim.
Yes, fixed. I will close it.
from jsbsim.
Related Issues (20)
- JSBSim Simulink Function HOT 36
- Rust HOT 13
- Can autopilot feature come to jsbsim- unreal engine 5? HOT 2
- MSVC: toupper is not a member of std HOT 1
- Missing target_include_directories in libJSBSim
- JSBSIM_ prefix in CMake options
- Cython warnings about 'tp_print' which is deprecated
- Wrong calculation of vPQRdot in FGAccelerations class HOT 4
- Fixing the mixture for JSBSim piston aircraft HOT 54
- Request: turbine spindown table or property support HOT 2
- Aircraft crashed on air when rolling consecutively HOT 15
- How Jsbsim models the "+" shaped tail fins of missiles and rockets. HOT 1
- JSBSimFlightDynamicsModel could not be loaded in Unreal Engine HOT 4
- AugmentCmd should be clamped to [0.0..1.0] HOT 4
- Trim succeeds and results in NaN values HOT 1
- JSBSim and s-function have different results and different reactivity themselves HOT 1
- Building for Unreal 5 on Linux not working HOT 7
- Javascript alternative? HOT 2
- Linearization and simplex trim from console executable and xml script HOT 16
- FGTurbine Shutdown Spin HOT 1
Recommend Projects
-
React
A declarative, efficient, and flexible JavaScript library for building user interfaces.
-
Vue.js
🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.
-
Typescript
TypeScript is a superset of JavaScript that compiles to clean JavaScript output.
-
TensorFlow
An Open Source Machine Learning Framework for Everyone
-
Django
The Web framework for perfectionists with deadlines.
-
Laravel
A PHP framework for web artisans
-
D3
Bring data to life with SVG, Canvas and HTML. 📊📈🎉
-
Recommend Topics
-
javascript
JavaScript (JS) is a lightweight interpreted programming language with first-class functions.
-
web
Some thing interesting about web. New door for the world.
-
server
A server is a program made to process requests and deliver data to clients.
-
Machine learning
Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.
-
Visualization
Some thing interesting about visualization, use data art
-
Game
Some thing interesting about game, make everyone happy.
Recommend Org
-
Facebook
We are working to build community through open source technology. NB: members must have two-factor auth.
-
Microsoft
Open source projects and samples from Microsoft.
-
Google
Google ❤️ Open Source for everyone.
-
Alibaba
Alibaba Open Source for everyone
-
D3
Data-Driven Documents codes.
-
Tencent
China tencent open source team.
from jsbsim.