diff --git a/src/mavesp8266.cpp b/src/mavesp8266.cpp index baa20134..7e0e3956 100644 --- a/src/mavesp8266.cpp +++ b/src/mavesp8266.cpp @@ -201,3 +201,24 @@ void MavESP8266Bridge::handle_non_mavlink(uint8_t b, bool msgReceived) } _last_parse_state = _rxstatus.parse_state; } + +/* + helper to check if a message is restricted to pass through the bridge +*/ +bool MavESP8266Bridge::restricted_message(mavlink_message_t* message) +{ + if (getWorld()->getParameters()->getWifiCastMode() != CAST_MODE_CONS_MULTI) { + // restrict messages only in conservative multicast mode + return false; + } + + // allowed messages + switch(message->msgid) { + case MAVLINK_MSG_ID_GLOBAL_POSITION_INT: + case MAVLINK_MSG_ID_FOLLOW_TARGET: + return false; + } + + // restrict all other messages + return true; +} diff --git a/src/mavesp8266.h b/src/mavesp8266.h index 4611e8d6..0a4d9d17 100644 --- a/src/mavesp8266.h +++ b/src/mavesp8266.h @@ -121,6 +121,7 @@ class MavESP8266Bridge { mavlink_status_t _rxstatus; void handle_non_mavlink(uint8_t b, bool msgReceived); + bool restricted_message(mavlink_message_t* message); uint8_t _non_mavlink_buffer[270]; uint16_t _non_mavlink_len; mavlink_parse_state_t _last_parse_state; diff --git a/src/mavesp8266_gcs.cpp b/src/mavesp8266_gcs.cpp index 4f23d190..88e39e55 100644 --- a/src/mavesp8266_gcs.cpp +++ b/src/mavesp8266_gcs.cpp @@ -55,11 +55,21 @@ void MavESP8266GCS::begin(MavESP8266Bridge* forwardTo, IPAddress gcsIP) { MavESP8266Bridge::begin(forwardTo); - _ip = gcsIP; + //-- Init variables that shouldn't change unless we reboot - _udp_port = getWorld()->getParameters()->getWifiUdpHport(); //-- Start UDP - _udp.begin(getWorld()->getParameters()->getWifiUdpCport()); + switch(getWorld()->getParameters()->getWifiCastMode()) { + case CAST_MODE_UNI: + _ip = gcsIP; + _udp_port = getWorld()->getParameters()->getWifiUdpHport(); + _udp.begin(getWorld()->getParameters()->getWifiUdpCport()); + break; + case CAST_MODE_FULL_MULTI ... CAST_MODE_CONS_MULTI: + _ip = getWorld()->getParameters()->getWifiMcastIP(); + _udp_port = getWorld()->getParameters()->getWifiMcastPort(); + _udp.beginMulticast(WiFi.localIP(), _ip, _udp_port); + break; + } } //--------------------------------------------------------------------------------- @@ -70,7 +80,9 @@ MavESP8266GCS::readMessage() //-- Read UDP if(_readMessage()) { //-- If we have a message, forward it - _forwardTo->sendMessage(&_message); + if(!restricted_message(&_message)) { + _forwardTo->sendMessage(&_message); + } memset(&_message, 0, sizeof(_message)); } uint32_t now = millis(); @@ -120,48 +132,50 @@ MavESP8266GCS::_readMessage() if(msgReceived) { //-- We no longer need to broadcast _status.packets_received++; - if(_ip[3] == 255) { - _ip = _udp.remoteIP(); - getWorld()->getLogger()->log("Response from GCS. Setting GCS IP to: %s\n", _ip.toString().c_str()); - } - //-- First packets - if(!_heard_from) { - if(_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { - //-- We no longer need DHCP - if(getWorld()->getParameters()->getWifiMode() == WIFI_MODE_AP) { - wifi_softap_dhcps_stop(); + if(getWorld()->getParameters()->getWifiCastMode() == CAST_MODE_UNI) { + if (_ip[3] == 255) { + _ip = _udp.remoteIP(); + getWorld()->getLogger()->log("Response from GCS. Setting GCS IP to: %s\n", _ip.toString().c_str()); + } + //-- First packets + if(!_heard_from) { + if(_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) { + //-- We no longer need DHCP + if(getWorld()->getParameters()->getWifiMode() == WIFI_MODE_AP) { + wifi_softap_dhcps_stop(); + } + _heard_from = true; + _system_id = _message.sysid; + _component_id = _message.compid; + _seq_expected = _message.seq + 1; + _last_heartbeat = millis(); } - _heard_from = true; - _system_id = _message.sysid; - _component_id = _message.compid; - _seq_expected = _message.seq + 1; - _last_heartbeat = millis(); + } else { + if(_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) + _last_heartbeat = millis(); + _checkLinkErrors(&_message); } - } else { - if(_message.msgid == MAVLINK_MSG_ID_HEARTBEAT) - _last_heartbeat = millis(); - _checkLinkErrors(&_message); - } - if (msgReceived == MAVLINK_FRAMING_BAD_CRC) { - // we don't process messages locally with bad CRC, - // but we do forward them, so when new messages - // are added we can bridge them - break; - } + if (msgReceived == MAVLINK_FRAMING_BAD_CRC) { + // we don't process messages locally with bad CRC, + // but we do forward them, so when new messages + // are added we can bridge them + break; + } #ifdef MAVLINK_FRAMING_BAD_SIGNATURE - if (msgReceived == MAVLINK_FRAMING_BAD_SIGNATURE) { - break; - } + if (msgReceived == MAVLINK_FRAMING_BAD_SIGNATURE) { + break; + } #endif - - //-- Check for message we might be interested - if(getWorld()->getComponent()->handleMessage(this, &_message)){ - //-- Eat message (don't send it to FC) - memset(&_message, 0, sizeof(_message)); - msgReceived = false; - continue; + + //-- Check for message we might be interested + if(getWorld()->getComponent()->handleMessage(this, &_message)){ + //-- Eat message (don't send it to FC) + memset(&_message, 0, sizeof(_message)); + msgReceived = false; + continue; + } } @@ -171,7 +185,7 @@ MavESP8266GCS::_readMessage() } } } - if(!msgReceived) { + if(!msgReceived && getWorld()->getParameters()->getWifiCastMode() == CAST_MODE_UNI) { if(_heard_from && (millis() - _last_heartbeat) > HEARTBEAT_TIMEOUT) { //-- Restart DHCP and start broadcasting again if(getWorld()->getParameters()->getWifiMode() == WIFI_MODE_AP) { @@ -223,6 +237,15 @@ MavESP8266GCS::sendMessage(mavlink_message_t* message) { int MavESP8266GCS::sendMessageRaw(uint8_t *buffer, int len) { + switch(getWorld()->getParameters()->getWifiCastMode()) { + case CAST_MODE_UNI: + _udp.beginPacket(_ip, _udp_port); + break; + + case CAST_MODE_FULL_MULTI ... CAST_MODE_CONS_MULTI: + _udp.beginPacketMulticast(_ip, _udp_port, WiFi.localIP()); + break; + } _udp.beginPacket(_ip, _udp_port); size_t sent = _udp.write(buffer, len); _udp.endPacket(); diff --git a/src/mavesp8266_httpd.cpp b/src/mavesp8266_httpd.cpp index 3ea8dad5..6f1d325e 100644 --- a/src/mavesp8266_httpd.cpp +++ b/src/mavesp8266_httpd.cpp @@ -66,6 +66,9 @@ const char* kDEBUG = "debug"; const char* kREBOOT = "reboot"; const char* kPOSITION = "position"; const char* kMODE = "mode"; +const char* kCASTMODE = "castmode"; +const char* kMCASTIP = "mcastip"; +const char* kMCASTPORT = "mcastport"; const char* kFlashMaps[7] = { "512KB (256/256)", @@ -325,6 +328,34 @@ static void handle_setup() message += "
"; + + message += "Casting Mode: "; + message += "getParameters()->getWifiCastMode() == CAST_MODE_UNI) { + message += " checked"; + } + message += ">Unicast\n"; + message += "getParameters()->getWifiCastMode() == CAST_MODE_FULL_MULTI) { + message += " checked"; + } + message += ">Full Multicast\n"; + message += "getParameters()->getWifiCastMode() == CAST_MODE_CONS_MULTI) { + message += " checked"; + } + message += ">Conservative Multicast
\n"; + + message += "Multicast IP: "; + message += "
"; + + message += "Multicast Port: "; + message += "
"; message += "Baudrate: "; message += "