JSBSim Flight Dynamics Model 1.3.1 (17 May 2026)
An Open Source Flight Dynamics and Control Software Library in C++
Loading...
Searching...
No Matches
FGInputSocket.cpp
1/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
2
3 Module: FGInputSocket.cpp
4 Author: Paul Chavent
5 Date started: 01/20/15
6 Purpose: Manage input of sim parameters to a socket
7 Called by: FGInput
8
9 ------------- Copyright (C) 2015 Paul Chavent -------------
10
11 This program is free software; you can redistribute it and/or modify it under
12 the terms of the GNU Lesser General Public License as published by the Free Software
13 Foundation; either version 2 of the License, or (at your option) any later
14 version.
15
16 This program is distributed in the hope that it will be useful, but WITHOUT
17 ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
18 FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License for more
19 details.
20
21 You should have received a copy of the GNU Lesser General Public License along with
22 this program; if not, write to the Free Software Foundation, Inc., 59 Temple
23 Place - Suite 330, Boston, MA 02111-1307, USA.
24
25 Further information about the GNU Lesser General Public License can also be found on
26 the world wide web at http://www.gnu.org.
27
28FUNCTIONAL DESCRIPTION
29--------------------------------------------------------------------------------
30This is the place where you create input routines to dump data for perusal
31later.
32
33HISTORY
34--------------------------------------------------------------------------------
3501/20/15 PC Created
36
37%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
38INCLUDES
39%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
40
41#include "FGInputSocket.h"
42#include "FGFDMExec.h"
43#include "models/FGAircraft.h"
44#include "FGXMLElement.h"
45#include "string_utilities.h"
46#include "FGLog.h"
47
48using namespace std;
49
50namespace JSBSim {
51
52/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
53CLASS IMPLEMENTATION
54%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
55
56FGInputSocket::FGInputSocket(FGFDMExec* fdmex, bool isEnabled) :
57 FGInputType(fdmex, isEnabled), SockProtocol(FGfdmSocket::ptTCP),
58 BlockingInput(false)
59{
60}
61
62//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
63
65{
66 if (!FGInputType::Load(el))
67 return false;
68
69 SockPort = atoi(el->GetAttributeValue("port").c_str());
70
71 if (SockPort == 0) {
72 FGXMLLogging log(el, LogLevel::ERROR);
73 log << "No port assigned in input element\n";
74 return false;
75 }
76
77 string action = el->GetAttributeValue("action");
78 if (to_upper(action) == "BLOCKING_INPUT")
79 BlockingInput = true;
80
81 return true;
82}
83
84//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
85
87{
89 return false;
90
91 if (enabled)
92 return CreateSocket();
93
94 return true;
95}
96
97//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
98
99bool FGInputSocket::CreateSocket()
100{
101 socket = std::make_unique<FGfdmSocket>(SockPort, SockProtocol);
102
103 if (!socket) return false;
104 if (!socket->GetConnectStatus()) return false;
105
106 return true;
107}
108
109//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
110
112{
113 if (enabled) return; // already enabled
115 CreateSocket();
116}
117
118//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
119
121{
123 socket.reset();
124}
125
126//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
127
129{
130 bool enabled_status = FGInputType::Toggle();
131 if (enabled_status)
132 CreateSocket();
133 else
134 socket.reset();
135
136 return enabled_status;
137}
138
139//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
140
141void FGInputSocket::Read(bool Holding)
142{
143 if (!socket) return;
144 if (!socket->GetConnectStatus()) return;
145
146 if (BlockingInput)
147 socket->WaitUntilReadable(); // block until a transmission is received
148
149 string raw_data = socket->Receive(); // read data
150
151 if (!raw_data.empty()) {
152 size_t start = 0;
153
154 data += raw_data;
155
156 // parse lines
157 while (1) {
158 size_t string_start = data.find_first_not_of("\r\n", start);
159 if (string_start == string::npos) break;
160 size_t string_end = data.find_first_of("\r\n", string_start);
161 if (string_end == string::npos) break;
162 string line = data.substr(string_start, string_end-string_start);
163 if (line.empty()) break;
164
165 // now parse individual line
166 vector <string> tokens = split(line,' ');
167
168 string command, argument, str_value;
169 if (!tokens.empty()) {
170 command = to_lower(tokens[0]);
171 if (tokens.size() > 1) {
172 argument = trim(tokens[1]);
173 if (tokens.size() > 2) {
174 str_value = trim(tokens[2]);
175 }
176 }
177 }
178
179 if (command == "set") { // SET PROPERTY
180 SGPropertyNode* node = nullptr;
181
182 if (argument.empty()) {
183 socket->Reply("No property argument supplied.\r\n");
184 break;
185 }
186 try {
187 node = PropertyManager->GetNode(argument);
188 } catch(...) {
189 socket->Reply("Badly formed property query\r\n");
190 break;
191 }
192
193 if (!node) {
194 socket->Reply("Unknown property\r\n");
195 break;
196 } else if (!node->hasValue()) {
197 socket->Reply("Not a leaf property\r\n");
198 break;
199 } else {
200 try {
201 double value = atof_locale_c(str_value);
202 node->setDoubleValue(value);
203 } catch(InvalidNumber& e) {
204 string msg(e.what());
205 msg += "\r\n";
206 socket->Reply(msg);
207 break;
208 }
209 }
210 socket->Reply("set successful\r\n");
211
212 } else if (command == "get") { // GET PROPERTY
213 SGPropertyNode* node = nullptr;
214
215 if (argument.empty()) {
216 socket->Reply("No property argument supplied.\r\n");
217 break;
218 }
219 try {
220 node = PropertyManager->GetNode(argument);
221 } catch(...) {
222 socket->Reply("Badly formed property query\r\n");
223 break;
224 }
225
226 if (!node) {
227 socket->Reply("Unknown property\r\n");
228 break;
229 } else if (!node->hasValue()) {
230 if (Holding) { // if holding can query property list
231 string query = FDMExec->QueryPropertyCatalog(argument, "\r\n");
232 socket->Reply(query);
233 } else {
234 socket->Reply("Must be in HOLD to search properties\r\n");
235 }
236 } else {
237 ostringstream buf;
238 buf << argument << " = " << setw(12) << setprecision(6) << node->getDoubleValue() << '\r' << endl;
239 socket->Reply(buf.str());
240 }
241
242 } else if (command == "hold") { // PAUSE
243
244 FDMExec->Hold();
245 socket->Reply("Holding\r\n");
246
247 } else if (command == "resume") { // RESUME
248
249 FDMExec->Resume();
250 socket->Reply("Resuming\r\n");
251
252 } else if (command == "iterate") { // ITERATE
253
254 int argumentInt;
255 istringstream (argument) >> argumentInt;
256 if (argument.empty()) {
257 socket->Reply("No argument supplied for number of iterations.\r\n");
258 break;
259 }
260 if ( !(argumentInt > 0) ){
261 socket->Reply("Required argument must be a positive Integer.\r\n");
262 break;
263 }
264 FDMExec->EnableIncrementThenHold( argumentInt );
265 FDMExec->Resume();
266 socket->Reply("Iterations performed\r\n");
267
268 } else if (command == "quit") { // QUIT
269
270 // close the socket connection
271 socket->Send("Closing connection\r\n");
272 socket->Close();
273
274 } else if (command == "info") { // INFO
275
276 // get info about the sim run and/or aircraft, etc.
277 ostringstream info;
278 info << "JSBSim version: " << JSBSim_version << "\r\n";
279 info << "Config File version: " << needed_cfg_version << "\r\n";
280 info << "Aircraft simulated: " << FDMExec->GetAircraft()->GetAircraftName() << "\r\n";
281 info << "Simulation time: " << setw(8) << setprecision(3) << FDMExec->GetSimTime() << '\r' << endl;
282 socket->Reply(info.str());
283
284 } else if (command == "help") { // HELP
285
286 socket->Reply(
287 " JSBSim Server commands:\r\n\r\n"
288 " get {property name}\r\n"
289 " set {property name} {value}\r\n"
290 " hold\r\n"
291 " resume\r\n"
292 " iterate {value}\r\n"
293 " help\r\n"
294 " quit\r\n"
295 " info\r\n\r\n");
296
297 } else {
298 socket->Reply(string("Unknown command: ") + command + "\r\n");
299 }
300
301 start = string_end;
302 }
303
304 // Remove processed commands.
305 size_t last_crlf = data.find_last_of("\r\n");
306 if (last_crlf != string::npos) {
307 if (last_crlf < data.length()-1)
308 data = data.substr(last_crlf+1);
309 else
310 data.clear();
311 }
312 }
313
314}
315
316}
std::string GetAttributeValue(const std::string &key)
Retrieves an attribute.
Encapsulates the JSBSim simulation executive.
Definition FGFDMExec.h:185
std::shared_ptr< FGAircraft > GetAircraft(void) const
Returns the FGAircraft pointer.
std::string QueryPropertyCatalog(const std::string &check, const std::string &end_of_line="\n")
Retrieves property or properties matching the supplied string.
void EnableIncrementThenHold(int Timesteps)
Turn on hold after increment.
Definition FGFDMExec.h:495
void Resume(void)
Resumes execution from a "Hold".
Definition FGFDMExec.h:499
double GetSimTime(void) const
Returns the cumulative simulation time in seconds.
Definition FGFDMExec.h:554
void Hold(void)
Pauses execution by preventing time from incrementing.
Definition FGFDMExec.h:493
bool Load(Element *el) override
Init the input directives from an XML file.
FGInputSocket(FGFDMExec *fdmex, bool isEnabled)
Constructor.
void Disable() override
Disables the input generation.
bool Toggle() override
Toggles the input generation.
void Read(bool Holding) override
Generates the input.
bool InitModel(void) override
Initializes the instance.
void Enable() override
Methods to enable, disable and toggle the input.
Abstract class to provide functions generic to all the input directives.
Definition FGInputType.h:74
bool Load(Element *el) override
Init the input directives from an XML file (implement the FGModel interface).
virtual bool Toggle(void)
Toggles the input generation.
virtual void Enable(void)
Enables the input generation.
virtual void Disable(void)
Disables the input generation.
bool InitModel(void) override
Init the input model according to its configitation.
The FGfdmSocket class enables JSBSim to communicate via sockets.
Definition FGfdmSocket.h:76
A node in a property tree.
Definition props.hxx:747
double getDoubleValue() const
Get a double value for this node.
bool setDoubleValue(double value)
Set a double value for this node.
bool hasValue() const
Test whether this node contains a primitive leaf value.
Definition props.hxx:810
Main namespace for the JSBSim Flight Dynamics Model.
Definition FGFDMExec.cpp:71