41#include "FGInputSocket.h"
43#include "models/FGAircraft.h"
44#include "FGXMLElement.h"
45#include "string_utilities.h"
80 log <<
"No port assigned in input element\n";
85 if (to_upper(action) ==
"BLOCKING_INPUT")
99 if (socket == 0)
return false;
118 string raw_data = socket->
Receive();
120 if (!raw_data.empty()) {
127 size_t string_start = data.find_first_not_of(
"\r\n", start);
128 if (string_start == string::npos)
break;
129 size_t string_end = data.find_first_of(
"\r\n", string_start);
130 if (string_end == string::npos)
break;
131 string line = data.substr(string_start, string_end-string_start);
132 if (line.empty())
break;
135 vector <string> tokens = split(line,
' ');
137 string command, argument, str_value;
138 if (!tokens.empty()) {
139 command = to_lower(tokens[0]);
140 if (tokens.size() > 1) {
141 argument = trim(tokens[1]);
142 if (tokens.size() > 2) {
143 str_value = trim(tokens[2]);
148 if (command ==
"set") {
151 if (argument.empty()) {
152 socket->
Reply(
"No property argument supplied.\r\n");
156 node = PropertyManager->GetNode(argument);
158 socket->
Reply(
"Badly formed property query\r\n");
163 socket->
Reply(
"Unknown property\r\n");
166 socket->
Reply(
"Not a leaf property\r\n");
170 double value = atof_locale_c(str_value);
173 string msg(e.what());
179 socket->
Reply(
"set successful\r\n");
181 }
else if (command ==
"get") {
184 if (argument.empty()) {
185 socket->
Reply(
"No property argument supplied.\r\n");
189 node = PropertyManager->GetNode(argument);
191 socket->
Reply(
"Badly formed property query\r\n");
196 socket->
Reply(
"Unknown property\r\n");
201 socket->
Reply(query);
203 socket->
Reply(
"Must be in HOLD to search properties\r\n");
207 buf << argument <<
" = " << setw(12) << setprecision(6) << node->
getDoubleValue() <<
'\r' << endl;
208 socket->
Reply(buf.str());
211 }
else if (command ==
"hold") {
214 socket->
Reply(
"Holding\r\n");
216 }
else if (command ==
"resume") {
219 socket->
Reply(
"Resuming\r\n");
221 }
else if (command ==
"iterate") {
224 istringstream (argument) >> argumentInt;
225 if (argument.empty()) {
226 socket->
Reply(
"No argument supplied for number of iterations.\r\n");
229 if ( !(argumentInt > 0) ){
230 socket->
Reply(
"Required argument must be a positive Integer.\r\n");
235 socket->
Reply(
"Iterations performed\r\n");
237 }
else if (command ==
"quit") {
240 socket->
Send(
"Closing connection\r\n");
243 }
else if (command ==
"info") {
247 info <<
"JSBSim version: " << JSBSim_version <<
"\r\n";
248 info <<
"Config File version: " << needed_cfg_version <<
"\r\n";
249 info <<
"Aircraft simulated: " << FDMExec->
GetAircraft()->GetAircraftName() <<
"\r\n";
250 info <<
"Simulation time: " << setw(8) << setprecision(3) << FDMExec->
GetSimTime() <<
'\r' << endl;
251 socket->
Reply(info.str());
253 }
else if (command ==
"help") {
256 " JSBSim Server commands:\r\n\r\n"
257 " get {property name}\r\n"
258 " set {property name} {value}\r\n"
261 " iterate {value}\r\n"
267 socket->
Reply(
string(
"Unknown command: ") + command +
"\r\n");
274 size_t last_crlf = data.find_last_of(
"\r\n");
275 if (last_crlf != string::npos) {
276 if (last_crlf < data.length()-1)
277 data = data.substr(last_crlf+1);
std::string GetAttributeValue(const std::string &key)
Retrieves an attribute.
Encapsulates the JSBSim simulation executive.
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.
void Resume(void)
Resumes execution from a "Hold".
double GetSimTime(void) const
Returns the cumulative simulation time in seconds.
void Hold(void)
Pauses execution by preventing time from incrementing.
The FGfdmSocket class enables JSBSim to communicate via sockets.
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.
A node in a property tree.
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.
Main namespace for the JSBSim Flight Dynamics Model.