Browse Source

Connection to last_letter once again successful

master
Georacer 8 years ago committed by Andrew Tridgell
parent
commit
54c1efe5e1
  1. 27
      libraries/SITL/SIM_last_letter.cpp
  2. 2
      libraries/SITL/SIM_last_letter.h

27
libraries/SITL/SIM_last_letter.cpp

@ -53,40 +53,25 @@ last_letter::last_letter(const char *home_str, const char *_frame_str) :
void last_letter::start_last_letter(void) void last_letter::start_last_letter(void)
{ {
pid_t child_pid = fork(); pid_t child_pid = fork();
if (child_pid != 0) { if (child_pid == 0) {
return;
}
// in child // in child
close(0); close(0);
open("/dev/null", O_RDONLY); open("/dev/null", O_RDONLY);
for (uint8_t i=3; i<100; i++) { for (uint8_t i=3; i<100; i++) {
close(i); close(i);
} }
char argHome[50];
sprintf(argHome,"home:=[%f,%f,%f]",home.lat*1.0e-7,home.lng*1.0e-7,(double)home.alt*1.0e-2);
const char *uav_name = strchr(frame_str, ':');
if (uav_name != NULL) {
uav_name++;
}
int ret = execlp("roslaunch", int ret = execlp("roslaunch",
"roslaunch", "roslaunch",
"last_letter", "last_letter",
"launcher.launch", "gazebo.launch",
"ArduPlane:=true", "ArduPlane:=true",
"simRate:=500",
"deltaT:=0.002",
argHome,
uav_name,
NULL); NULL);
if (ret != 0) { if (ret != 0) {
perror("roslaunch"); perror("roslaunch");
} }
exit(1); exit(1);
} }
}
/* /*
send servos send servos
@ -125,8 +110,6 @@ void last_letter::recv_fdm(const struct sitl_input &input)
airspeed = pkt.airspeed; airspeed = pkt.airspeed;
airspeed_pitot = pkt.airspeed; airspeed_pitot = pkt.airspeed;
// update magnetic field
update_mag_field_bf();
// auto-adjust to last_letter frame rate // auto-adjust to last_letter frame rate
uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us; uint64_t deltat_us = pkt.timestamp_us - last_timestamp_us;
@ -146,6 +129,10 @@ void last_letter::update(const struct sitl_input &input)
send_servos(input); send_servos(input);
recv_fdm(input); recv_fdm(input);
sync_frame_time(); sync_frame_time();
update_position();
// update magnetic field
update_mag_field_bf();
} }
} // namespace SITL } // namespace SITL

2
libraries/SITL/SIM_last_letter.h

@ -41,7 +41,7 @@ public:
} }
private: private:
static const uint16_t fdm_port = 9002; static const uint16_t fdm_port = 5002;
/* /*
packet sent to last_letter packet sent to last_letter

Loading…
Cancel
Save