Reverted change to src/modules/simulator/simulator_mavlink.cpp

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2016-01-21 12:18:17 -08:00 committed by Julian Oes
parent ae0d0e67cc
commit 4c7ec2b0ff

View File

@ -530,13 +530,8 @@ 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
mavlink_status_t udp_status = {};
mavlink_status_t serial_status = {};
bool sim_delay = false;
@ -580,10 +575,9 @@ void Simulator::pollForMAVLinkMessages(bool publish)
if (len > 0) {
mavlink_message_t msg;
mavlink_status_t status;
for (int i = 0; i < len; i++) {
if (mavlink_parse_char(MAVLINK_COMM_0, _buf[i], &msg, &status)) {
if (mavlink_parse_char(MAVLINK_COMM_0, _buf[i], &msg, &udp_status)) {
// have a message, handle it
handle_message(&msg, publish);
}
@ -597,10 +591,9 @@ void Simulator::pollForMAVLinkMessages(bool publish)
if (len > 0) {
mavlink_message_t msg;
mavlink_status_t status;
for (int i = 0; i < len; ++i) {
if (mavlink_parse_char(MAVLINK_COMM_0, serial_buf[i], &msg, &status)) {
if (mavlink_parse_char(MAVLINK_COMM_1, serial_buf[i], &msg, &serial_status)) {
// have a message, handle it
handle_message(&msg, true);
}