Sim: minor cleanups

This commit is contained in:
Lorenz Meier
2015-12-29 14:17:59 +01:00
parent 5d6f63af19
commit 5dc4ea8146
+8 -10
View File
@@ -426,6 +426,13 @@ void Simulator::initializeSensorData()
void Simulator::pollForMAVLinkMessages(bool publish)
{
// set the threads name
#ifdef __PX4_DARWIN
pthread_setname_np("sim_rcv");
#else
pthread_setname_np(pthread_self(), "sim_rcv");
#endif
// udp socket data
struct sockaddr_in _myaddr;
const int _port = UDP_PORT;
@@ -504,14 +511,13 @@ void Simulator::pollForMAVLinkMessages(bool publish)
pret = ::poll(&fds[0], fd_count, 100);
}
PX4_INFO("Found initial message, pret = %d", pret);
_initialized = true;
// reset system time
(void)hrt_reset();
if (fds[0].revents & POLLIN) {
len = recvfrom(_fd, _buf, sizeof(_buf), 0, (struct sockaddr *)&_srcaddr, &_addrlen);
PX4_INFO("Sending initial controls message to jMAVSim.");
PX4_INFO("Sending initial controls message to simulator");
send_controls();
}
@@ -523,14 +529,6 @@ void Simulator::pollForMAVLinkMessages(bool publish)
pthread_create(&sender_thread, &sender_thread_attr, Simulator::sending_trampoline, NULL);
pthread_attr_destroy(&sender_thread_attr);
// set the threads name
#ifdef __PX4_DARWIN
pthread_setname_np("sim_rcv");
#else
pthread_setname_np(pthread_self(), "sim_rcv");
#endif
// wait for new mavlink messages to arrive
while (true) {