MAVLink: send streams on both mavlink interfaces

when doing init the user may be on the Xbee port

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2996 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-08-01 10:08:59 +00:00
parent 5f9c03ca77
commit 261c7edec9

View File

@ -1129,7 +1129,7 @@ GCS_MAVLINK::_queued_send()
#endif // GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK || HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK
static void send_rate(uint8_t low, uint8_t high) {
static void send_rate(uint16_t low, uint16_t high) {
#if GCS_PROTOCOL == GCS_PROTOCOL_MAVLINK
gcs.data_stream_send(low, high);
#endif
@ -1158,15 +1158,15 @@ static void mavlink_delay(unsigned long t)
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0)
hil.send_message(MSG_HEARTBEAT);
#endif
hil.data_stream_send(1,3);
send_rate(1, 3);
}
if (tnow - last_3hz > 333) {
last_3hz = tnow;
hil.data_stream_send(3,5);
send_rate(3, 5);
}
if (tnow - last_10hz > 100) {
last_10hz = tnow;
hil.data_stream_send(5,45);
send_rate(5, 45);
}
if (tnow - last_50hz > 20) {
last_50hz = tnow;
@ -1174,7 +1174,7 @@ static void mavlink_delay(unsigned long t)
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && (HIL_MODE != HIL_MODE_DISABLED || HIL_PORT == 0)
hil.update();
#endif
hil.data_stream_send(45,1000);
send_rate(45, 1000);
}
delay(1);
} while (millis() - tstart < t);