JSBSim Flight Dynamics Model 1.2.2 (22 Mar 2025)
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 <cstring>
42#include <cstdlib>
43#include <sstream>
44#include <iomanip>
45
46#include "FGInputSocket.h"
47#include "FGFDMExec.h"
48#include "models/FGAircraft.h"
49#include "input_output/FGXMLElement.h"
50#include "input_output/string_utilities.h"
51
52using namespace std;
53
54namespace JSBSim {
55
56/*%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
57CLASS IMPLEMENTATION
58%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%*/
59
61 FGInputType(fdmex), socket(0), SockProtocol(FGfdmSocket::ptTCP),
62 BlockingInput(false)
63{
64}
65
66//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
67
69{
70 delete socket;
71}
72
73//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
74
76{
77 if (!FGInputType::Load(el))
78 return false;
79
80 SockPort = atoi(el->GetAttributeValue("port").c_str());
81
82 if (SockPort == 0) {
83 cerr << endl << "No port assigned in input element" << endl;
84 return false;
85 }
86
87 string action = el->GetAttributeValue("action");
88 if (to_upper(action) == "BLOCKING_INPUT")
89 BlockingInput = true;
90
91 return true;
92}
93
94//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
95
97{
99 delete socket;
100 socket = new FGfdmSocket(SockPort, SockProtocol);
101
102 if (socket == 0) return false;
103 if (!socket->GetConnectStatus()) return false;
104
105 return true;
106 }
107
108 return false;
109}
110
111//%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
112
113void FGInputSocket::Read(bool Holding)
114{
115 if (!socket) return;
116 if (!socket->GetConnectStatus()) return;
117
118 if (BlockingInput)
119 socket->WaitUntilReadable(); // block until a transmission is received
120
121 string raw_data = socket->Receive(); // read data
122
123 if (!raw_data.empty()) {
124 size_t start = 0;
125
126 data += raw_data;
127
128 // parse lines
129 while (1) {
130 size_t string_start = data.find_first_not_of("\r\n", start);
131 if (string_start == string::npos) break;
132 size_t string_end = data.find_first_of("\r\n", string_start);
133 if (string_end == string::npos) break;
134 string line = data.substr(string_start, string_end-string_start);
135 if (line.empty()) break;
136
137 // now parse individual line
138 vector <string> tokens = split(line,' ');
139
140 string command, argument, str_value;
141 if (!tokens.empty()) {
142 command = to_lower(tokens[0]);
143 if (tokens.size() > 1) {
144 argument = trim(tokens[1]);
145 if (tokens.size() > 2) {
146 str_value = trim(tokens[2]);
147 }
148 }
149 }
150
151 if (command == "set") { // SET PROPERTY
152 FGPropertyNode* node = nullptr;
153
154 if (argument.empty()) {
155 socket->Reply("No property argument supplied.\r\n");
156 break;
157 }
158 try {
159 node = PropertyManager->GetNode(argument);
160 } catch(...) {
161 socket->Reply("Badly formed property query\r\n");
162 break;
163 }
164
165 if (!node) {
166 socket->Reply("Unknown property\r\n");
167 break;
168 } else if (!node->hasValue()) {
169 socket->Reply("Not a leaf property\r\n");
170 break;
171 } else {
172 try {
173 double value = atof_locale_c(str_value);
174 node->setDoubleValue(value);
175 } catch(InvalidNumber& e) {
176 string msg(e.what());
177 msg += "\r\n";
178 socket->Reply(msg);
179 break;
180 }
181 }
182 socket->Reply("set successful\r\n");
183
184 } else if (command == "get") { // GET PROPERTY
185 FGPropertyNode* node = nullptr;
186
187 if (argument.empty()) {
188 socket->Reply("No property argument supplied.\r\n");
189 break;
190 }
191 try {
192 node = PropertyManager->GetNode(argument);
193 } catch(...) {
194 socket->Reply("Badly formed property query\r\n");
195 break;
196 }
197
198 if (!node) {
199 socket->Reply("Unknown property\r\n");
200 break;
201 } else if (!node->hasValue()) {
202 if (Holding) { // if holding can query property list
203 string query = FDMExec->QueryPropertyCatalog(argument, "\r\n");
204 socket->Reply(query);
205 } else {
206 socket->Reply("Must be in HOLD to search properties\r\n");
207 }
208 } else {
209 ostringstream buf;
210 buf << argument << " = " << setw(12) << setprecision(6) << node->getDoubleValue() << '\r' << endl;
211 socket->Reply(buf.str());
212 }
213
214 } else if (command == "hold") { // PAUSE
215
216 FDMExec->Hold();
217 socket->Reply("Holding\r\n");
218
219 } else if (command == "resume") { // RESUME
220
221 FDMExec->Resume();
222 socket->Reply("Resuming\r\n");
223
224 } else if (command == "iterate") { // ITERATE
225
226 int argumentInt;
227 istringstream (argument) >> argumentInt;
228 if (argument.empty()) {
229 socket->Reply("No argument supplied for number of iterations.\r\n");
230 break;
231 }
232 if ( !(argumentInt > 0) ){
233 socket->Reply("Required argument must be a positive Integer.\r\n");
234 break;
235 }
236 FDMExec->EnableIncrementThenHold( argumentInt );
237 FDMExec->Resume();
238 socket->Reply("Iterations performed\r\n");
239
240 } else if (command == "quit") { // QUIT
241
242 // close the socket connection
243 socket->Send("Closing connection\r\n");
244 socket->Close();
245
246 } else if (command == "info") { // INFO
247
248 // get info about the sim run and/or aircraft, etc.
249 ostringstream info;
250 info << "JSBSim version: " << JSBSim_version << "\r\n";
251 info << "Config File version: " << needed_cfg_version << "\r\n";
252 info << "Aircraft simulated: " << FDMExec->GetAircraft()->GetAircraftName() << "\r\n";
253 info << "Simulation time: " << setw(8) << setprecision(3) << FDMExec->GetSimTime() << '\r' << endl;
254 socket->Reply(info.str());
255
256 } else if (command == "help") { // HELP
257
258 socket->Reply(
259 " JSBSim Server commands:\r\n\r\n"
260 " get {property name}\r\n"
261 " set {property name} {value}\r\n"
262 " hold\r\n"
263 " resume\r\n"
264 " iterate {value}\r\n"
265 " help\r\n"
266 " quit\r\n"
267 " info\r\n\r\n");
268
269 } else {
270 socket->Reply(string("Unknown command: ") + command + "\r\n");
271 }
272
273 start = string_end;
274 }
275
276 // Remove processed commands.
277 size_t last_crlf = data.find_last_of("\r\n");
278 if (last_crlf != string::npos) {
279 if (last_crlf < data.length()-1)
280 data = data.substr(last_crlf+1);
281 else
282 data.clear();
283 }
284 }
285
286}
287
288}
std::string GetAttributeValue(const std::string &key)
Retrieves an attribute.
Encapsulates the JSBSim simulation executive.
Definition FGFDMExec.h:184
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:490
void Resume(void)
Resumes execution from a "Hold".
Definition FGFDMExec.h:494
double GetSimTime(void) const
Returns the cumulative simulation time in seconds.
Definition FGFDMExec.h:549
void Hold(void)
Pauses execution by preventing time from incrementing.
Definition FGFDMExec.h:488
bool Load(Element *el) override
Init the input directives from an XML file.
void Read(bool Holding) override
Generates the input.
bool InitModel(void) override
Initializes the instance.
~FGInputSocket() override
Destructor.
FGInputSocket(FGFDMExec *fdmex)
Constructor.
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).
bool InitModel(void) override
Init the input model according to its configitation.
Class wrapper for property handling.
The FGfdmSocket class enables JSBSim to communicate via sockets.
Definition FGfdmSocket.h:75
std::string Receive(void)
Receive data from the socket connection.
bool GetConnectStatus(void)
Return the connection status of the socket.
void Close(void)
Close the socket connection if the protocol is TCP.
void WaitUntilReadable(void)
Wait until the TCP socket is readable.
int Reply(const std::string &text)
Send a reply to the client ending by a prompt "JSBSim>".
void Send(void)
Send the internal buffer over the socket connection.