make the Xbee anti-brick delay configurabe

and change default to 2s

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3269 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-09-05 05:12:13 +00:00
parent cb64198759
commit 0a72520a93
2 changed files with 7 additions and 2 deletions

View File

@ -33,7 +33,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, uint8_t id, uint16_
#define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false #define CHECK_PAYLOAD_SIZE(id) if (payload_space < MAVLINK_MSG_ID_## id ##_LEN) return false
if (chan == MAVLINK_COMM_1 && millis() < 1000) { if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) {
// defer any messages on the telemetry port for 1 second after // defer any messages on the telemetry port for 1 second after
// bootup, to try to prevent bricking of Xbees // bootup, to try to prevent bricking of Xbees
return false; return false;
@ -399,7 +399,7 @@ static void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint16_t pa
void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str) void mavlink_send_text(mavlink_channel_t chan, uint8_t severity, const char *str)
{ {
if (chan == MAVLINK_COMM_0 && millis() < 1000) { if (chan == MAVLINK_COMM_1 && millis() < MAVLINK_TELEMETRY_PORT_DELAY) {
// don't send status MAVLink messages for 1 second after // don't send status MAVLink messages for 1 second after
// bootup, to try to prevent Xbee bricking // bootup, to try to prevent Xbee bricking
return; return;

View File

@ -715,3 +715,8 @@
#ifndef CLI_ENABLED #ifndef CLI_ENABLED
# define CLI_ENABLED ENABLED # define CLI_ENABLED ENABLED
#endif #endif
// delay to prevent Xbee bricking, in milliseconds
#ifndef MAVLINK_TELEMETRY_PORT_DELAY
# define MAVLINK_TELEMETRY_PORT_DELAY 2000
#endif