mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
revert debug items
This commit is contained in:
parent
52d5d690ff
commit
99557aec52
@ -392,7 +392,7 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
|
||||
|
||||
/* if not in normal mode, we are an onboard link
|
||||
* onboard links should only pass on messages from the same system ID */
|
||||
if ( self->_mode != MAVLINK_MODE_ONBOARD || msg->sysid == mavlink_system.sysid ) {
|
||||
if (!(self->_mode != MAVLINK_MODE_NORMAL && msg->sysid != mavlink_system.sysid)) {
|
||||
inst->pass_message(msg);
|
||||
}
|
||||
}
|
||||
|
||||
@ -44,6 +44,7 @@
|
||||
#include <nuttx/config.h>
|
||||
#include <unistd.h>
|
||||
#include <pthread.h>
|
||||
#include <stdio.h>
|
||||
#include <math.h>
|
||||
#include <stdbool.h>
|
||||
#include <fcntl.h>
|
||||
@ -1458,11 +1459,6 @@ MavlinkReceiver::receive_thread(void *arg)
|
||||
/* if read failed, this loop won't execute */
|
||||
for (ssize_t i = 0; i < nread; i++) {
|
||||
if (mavlink_parse_char(_mavlink->get_channel(), buf[i], &msg, &status)) {
|
||||
|
||||
printf("\n");
|
||||
printf("HANDLE MESSAGE\n");
|
||||
printf("MSGID:%i\n",msg.msgid);
|
||||
|
||||
/* handle generic messages and commands */
|
||||
handle_message(&msg);
|
||||
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user