mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed FDM UDP socket for JSBSim
needs to be uppercase for new versions also improved debug output
This commit is contained in:
parent
6bf40b74b1
commit
28a12224c3
|
@ -60,6 +60,11 @@ JSBSim::JSBSim(const char *home_str, const char *frame_str) :
|
|||
if (model_name != nullptr) {
|
||||
jsbsim_model = model_name + 1;
|
||||
}
|
||||
control_port = 5505 + instance*10;
|
||||
fdm_port = 5504 + instance*10;
|
||||
|
||||
printf("JSBSim backend started: control_port=%u fdm_port=%u\n",
|
||||
control_port, fdm_port);
|
||||
}
|
||||
|
||||
/*
|
||||
|
@ -70,12 +75,13 @@ bool JSBSim::create_templates(void)
|
|||
if (created_templates) {
|
||||
return true;
|
||||
}
|
||||
control_port = 5505 + instance*10;
|
||||
fdm_port = 5504 + instance*10;
|
||||
|
||||
asprintf(&jsbsim_script, "%s/jsbsim_start_%u.xml", autotest_dir, instance);
|
||||
asprintf(&jsbsim_fgout, "%s/jsbsim_fgout_%u.xml", autotest_dir, instance);
|
||||
|
||||
printf("JSBSim_script: '%s'\n", jsbsim_script);
|
||||
printf("JSBSim_fgout: '%s'\n", jsbsim_fgout);
|
||||
|
||||
FILE *f = fopen(jsbsim_script, "w");
|
||||
if (f == nullptr) {
|
||||
AP_HAL::panic("Unable to create jsbsim script %s", jsbsim_script);
|
||||
|
@ -126,12 +132,15 @@ bool JSBSim::create_templates(void)
|
|||
AP_HAL::panic("Unable to create jsbsim fgout script %s", jsbsim_fgout);
|
||||
}
|
||||
fprintf(f, "<?xml version=\"1.0\"?>\n"
|
||||
"<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"udp\" rate=\"1000\"/>\n",
|
||||
"<output name=\"127.0.0.1\" type=\"FLIGHTGEAR\" port=\"%u\" protocol=\"UDP\" rate=\"1000\"/>\n",
|
||||
fdm_port);
|
||||
fclose(f);
|
||||
|
||||
char *jsbsim_reset;
|
||||
asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model);
|
||||
|
||||
printf("JSBSim_reset: '%s'\n", jsbsim_reset);
|
||||
|
||||
f = fopen(jsbsim_reset, "w");
|
||||
if (f == nullptr) {
|
||||
AP_HAL::panic("Unable to create jsbsim reset script %s", jsbsim_reset);
|
||||
|
@ -439,14 +448,6 @@ void JSBSim::drain_control_socket()
|
|||
ssize_t received;
|
||||
do {
|
||||
received = sock_control.recv(buf, buflen, 0);
|
||||
if (received < 0) {
|
||||
if (errno != EAGAIN && errno != EWOULDBLOCK) {
|
||||
fprintf(stderr, "error recv on control socket: %s",
|
||||
strerror(errno));
|
||||
}
|
||||
} else {
|
||||
// fprintf(stderr, "received from control socket: %s\n", buf);
|
||||
}
|
||||
} while (received > 0);
|
||||
}
|
||||
/*
|
||||
|
|
Loading…
Reference in New Issue