Telnet communication: how to configure server to operate in blocking mode? #1079
Replies: 14 comments 19 replies
-
Just to be clear, you're saying that you haven't established a telnet connection? As opposed to you've established a connection but the telnet client is idle, i.e. isn't sending any data? So if you haven't established a connection then given line 115
So if that is the case, it isn't processing empty data packets, there is no connection to handle so it simply returns. jsbsim/src/input_output/FGInputSocket.cpp Lines 112 to 120 in d4f85bc The Out of interest how and what are you using JSBSim for via the telnet interface? |
Beta Was this translation helpful? Give feedback.
-
I've just checked once again, and it seems that
then this debug message outputs to console multiple times. What am I doing wrong? |
Beta Was this translation helpful? Give feedback.
-
I see a couple of issues in the JSBSim source code with regards to a telnet socket. So first off, note that the socket when it is created is set to non-blocking mode. Which means that when jsbsim/src/input_output/FGfdmSocket.cpp Lines 209 to 220 in d4f85bc The second issue is on line 114, the check should be jsbsim/src/input_output/FGInputSocket.cpp Lines 112 to 115 in d4f85bc So because of both of these issues you're seeing |
Beta Was this translation helpful? Give feedback.
-
I'll submit a pull request to fix the socket issues I mentioned above. But as a quick work-around for your build you could just update line 114 in FGInputSocket.cpp for now. Are you using ArduPilot SITL with JSBSim? https://ardupilot.org/dev/docs/sitl-with-jsbsim.html |
Beta Was this translation helpful? Give feedback.
-
thank you!
yes, that's it |
Beta Was this translation helpful? Give feedback.
-
So Ardupilot's SITL interface with JSBSim makes use of the telnet interface to send commands to JSBSim. So are you looking to re-implement the SITL interface to JSBSim in Ardupilot? Or are you wanting to keep the current Ardupilot SITL interface in place but you want some additional communication channel? If you give us some more details on what your current issues are with the SITL interface and what you're trying to achieve it might help us steer you in some direction. |
Beta Was this translation helpful? Give feedback.
-
Okay, so you have your own GCS, but I'm assuming it's compatible with MAVLink and I'm assuming you're also using Arduplane as the autopilot? And now instead of using FlightGear for visualization you want to use Unreal? If that is the case why not simply write some code to take the pose (position, attitude) data that JSBSim provides to then drive the pose in Unreal? In other words continue using all the other existing Arduplane SITL links to/from JSBSim. |
Beta Was this translation helpful? Give feedback.
-
On my side, this piece of code is bothering me: jsbsim/src/input_output/FGfdmSocket.cpp Lines 273 to 285 in d4f85bc This is Windows only code (not sure which platform @chekhovana and @airspector are using ? Has that been mentioned ?). This code basically hangs up as soon as it is no longer receiving data. For a telnet connection I think that would result in the immediate termination of the connection. I guess this piece of code is meant to save CPU cycles but I could not tell for sure. I'm suspecting that this strategy is too aggressive and that it causes the numerous failures of the unit test TestInputSocket.py on Windows for our CI workflow.
It may be related to this discussion topic if JSBSim is being run on Windows but it would not explain why |
Beta Was this translation helpful? Give feedback.
-
Not sure why there is that Windows specific code. If I compare the documentation for https://learn.microsoft.com/en-us/windows/win32/api/winsock/nf-winsock-recv They both return 0 when:
And if set to non-blocking then both return -1 (SOCKET_ERROR) if a call would block.
Not sure what platform @chekhovana and @airspector are using. |
Beta Was this translation helpful? Give feedback.
-
Hello @dpculp! No, I haven't tried UDP. Judging by the code, I expect the same issues as in case of using TCP sockets, as both socket types share the same implementation, aren't they? |
Beta Was this translation helpful? Give feedback.
-
@chekhovana Just letting you know that Pull Request #1081 is currently under review. It's expected to improve the management of socket errors and will log error messages in the console when a socket function encounters an error. This should assist in pinpointing the issue you've reported. |
Beta Was this translation helpful? Give feedback.
-
Hi @chekhovana, we've just merged a pull request that should resolve a few details and provide clearer error messages. Do you have the opportunity to compile the head of JSBSim master branch ? If so, could you please run some tests with the latest code of JSBSim and let us know if there are some improvements or new error messages issued while running your code ? Thanks. |
Beta Was this translation helpful? Give feedback.
-
JSBSim runs as a single threaded process. So in general with regards to the telnet interface you have JSBSim running at by default 120Hz and in realtime mode with a user flying the aircraft and then every now and then the user may type something into the telnet client to get some state data, or to set some state etc. and so in general you don't want to block and therefore pause the simulation waiting for the user to send a telnet command. Rather on each simulation timestep you check, in a non-blocking way whether there is any incoming telnet data, and if there is then read it and process it. But if there isn't any incoming telnet data then loop around again and execute the next simulation time step. If run in realtime mode there will generally be some amount of sleep in-between simulation time steps in order to keep to the simulation rate (default 120Hz). Now much later on there was a requirement for lock stepping with an external process, two examples being Ardupilot wanting to use JSBSim in SITL mode and also @agodemar wanting to interface with OpenFOAM as an external process providing 3D wind velocities. Which is what lead to the support for the You will see comments/suggestions about making JSBSim configurable to decide whether to only block on reading from a socket or also whether to allow it to block on the listen/accept for an incoming request, which we don't currently support. Note while reading the issue the mention of Ardupilot SITL and in particular it's use of You had mentioned making use of JSBSim via ArduPilot SITL which runs JSBSim and then makes use of the Does your setup differ to the standad ArduPilot SITL? Are you starting things differently etc.? Give us more details on what you're trying to do and what issue you see with JSBSim not blocking on the listen/accept. |
Beta Was this translation helpful? Give feedback.
-
@chekhovana thanks for the additional detail about your setup. I did mention the following previously:
However, thinking about it a bit more since you posted actually I think you should be able to get these 2 (ArduPilot SITL and atmosphere updates) concurrent telnet connections working with JSBSim today. So you'll see that ArduPilot SITL creates a telnet control port as part of the script template that it creates. So I'd suggest you simply create another telnet control port on a different port number, either by adding another one to the template script or by adding it to your JSBSim aircraft's FDM xml file. That way JSBSim will then have two telnet input channels listening for connections, with ArduPlane SITL connecting to the one and time stepping JSBSim while your program with the weather data can connect to the second telnet port and periodically send weather parameter updates. In this setup there should be no need to modify JSBSim's current telnet and socket handling code, just make sure that you don't set either telnet port to BTW, talking of non-blocking sockets you'll notice that ArduPilot SITL also makes use of non-blocking sockets. |
Beta Was this translation helpful? Give feedback.
-
Concerning communication with jsbsim through telnet, I can observe the following situation: when connection with client isn't established, then method:
jsbsim/src/input_output/FGInputSocket.cpp
Line 112 in d4f85bc
is invoked in loop, processing incoming empty data packets, which is quite CPU-consuming. The following setting:
<input port="1137" action="blocking_input"/>
doesn't help.
Is there any way to configure server socket to suspend and wait until some non-empty data packet arrives?
Thanks in advance
Beta Was this translation helpful? Give feedback.
All reactions