Compare commits

...

18 Commits

Author SHA1 Message Date
9be784f69b Improve cleanup in BLEClient (#4742)
- Remove client from the list of devices in case registration fails
- Filter other events not related to registration during registration phase
- Cleanup if connect fails
- Reset if after disconnect
- Disconnect callback *after* cleanup is done so object can be deleted

This fixes some of the issues I had like:
- `BLEClient::connect` hangs up and never recovered because registration failed
- `BLEClient` could not be deleted after disconnect or deletion creating ghost events https://github.com/espressif/arduino-esp32/issues/4047
- `BLEClient` could not be properly reused after a connection was attempted (successful or not) 

* Cleanup in case of registration and connect failure.
Cleanup before calling disconnect callback for safe delete.
Reject other events during registration.
Adresses #4047, #4055

* Clear if after unregister #4047
2021-02-16 11:21:45 +02:00
7cdfb8bc7c Refactor BLEAdvertisedDevice (#4739)
fixes #4596

* Prevent possible undefined behaviour by get methods not taking an index as parameter
* Add methods to get the count of service data UUIDs and service UUIDs
* Various code improvements
2021-02-16 11:02:58 +02:00
8134a42162 Fix leak of memory and possible crashes in AsyncUDP 2021-02-16 10:26:37 +02:00
f13ff65691 AsyncUDP: Added lastErr helper variable (#4789)
The variable is useful when debugging AsyncUDP send problems.
The upper application can read and analyze the error reason.
2021-02-16 02:21:53 +02:00
e831680a41 Fixed a memory leak in BLE (issue #4753) (#4761)
* Fixed crash on delete after disconnect

* Fixed memory leak when getting characteristics

* Removed guard

Co-authored-by: ushiboy <ushiboy.dev@gmail.com>
2021-02-16 01:50:24 +02:00
d964873840 Added more inclusive CORS policy (#4767) 2021-02-16 01:49:30 +02:00
7e8993fc83 Speed up upload by a factor of 17 (#4787)
* Speed up upload by a factor of 17

Uploads are very slow because of an unnecessary "client.connected()" check in _uploadReadByte().

Here is what happens:
client.connected() is called for every byte read.  WiFiClient::connected() calls recv(fd(), &dummy, 0, MSG_DONTWAIT); which takes a relatively long time, so the optimized path of returning a buffered byte via client.read() is effectively nullified.

Removing the one line changed the upload speed for a 2 MB file (discarding the received data) from 22 KB/sec (before) to 367 KB/sec (after).

The change is safe in the face of disconnects because client.read(), when it no longer has buffered data, calls (WiFiClient)  fillBuffer(), which calls recv(), so the disconnection will be detected in due course.

* Move disconnect check into the timeout loop
2021-02-16 01:47:01 +02:00
15bae92a72 Idf release/v3.3 d8082b7f3
* Update IDF to d8082b7f3
2021-02-16 01:37:37 +02:00
6f23cd5988 Make sure that HTTPClient disconnects from the old server if redirecting to new one
Fixes: https://github.com/espressif/arduino-esp32/issues/4763
2021-02-04 02:42:44 +02:00
ad4cf1461b Rework setHostname for WiFi STA
Fixes: https://github.com/espressif/arduino-esp32/issues/2537
2021-02-03 13:17:49 +02:00
5de03a3918 Fix WiFi STA config IP to INADDR_NONE results in 255.255.255.255
Fixes: https://github.com/espressif/arduino-esp32/issues/4732
2021-02-03 11:47:35 +02:00
4b385690bc Move default Arduino partitions to a separate section (#4747) 2021-01-27 13:52:39 +02:00
dd513df124 Add arm64 support for mkspiffs 2021-01-21 14:42:31 +02:00
cee659563d IDF release/v3.3 7e63061fa (#4726)
Co-authored-by: me-no-dev <me-no-dev@github.com>
2021-01-21 14:33:55 +02:00
55442a05a4 Remove an unused variable 'channel' (#4725) 2021-01-21 14:31:25 +02:00
c9b3e512dd Make BLERemoteCharacteristic::getRemoteService() public #3367 (#4735) 2021-01-21 14:30:33 +02:00
8d0e68db4f Added parameter to Preferences::begin to select non-default NVS partition (#4718) 2021-01-15 19:06:51 +02:00
d2530850a3 Copy platformio-build.py in the release package 2021-01-14 11:17:21 +02:00
108 changed files with 175 additions and 75 deletions

View File

@ -171,18 +171,19 @@ mkdir -p "$PKG_DIR/tools"
# Copy all core files to the package folder # Copy all core files to the package folder
echo "Copying files for packaging ..." echo "Copying files for packaging ..."
cp -f "$GITHUB_WORKSPACE/boards.txt" "$PKG_DIR/" cp -f "$GITHUB_WORKSPACE/boards.txt" "$PKG_DIR/"
cp -f "$GITHUB_WORKSPACE/programmers.txt" "$PKG_DIR/" cp -f "$GITHUB_WORKSPACE/programmers.txt" "$PKG_DIR/"
cp -Rf "$GITHUB_WORKSPACE/cores" "$PKG_DIR/" cp -Rf "$GITHUB_WORKSPACE/cores" "$PKG_DIR/"
cp -Rf "$GITHUB_WORKSPACE/libraries" "$PKG_DIR/" cp -Rf "$GITHUB_WORKSPACE/libraries" "$PKG_DIR/"
cp -Rf "$GITHUB_WORKSPACE/variants" "$PKG_DIR/" cp -Rf "$GITHUB_WORKSPACE/variants" "$PKG_DIR/"
cp -f "$GITHUB_WORKSPACE/tools/espota.exe" "$PKG_DIR/tools/" cp -f "$GITHUB_WORKSPACE/tools/espota.exe" "$PKG_DIR/tools/"
cp -f "$GITHUB_WORKSPACE/tools/espota.py" "$PKG_DIR/tools/" cp -f "$GITHUB_WORKSPACE/tools/espota.py" "$PKG_DIR/tools/"
cp -f "$GITHUB_WORKSPACE/tools/esptool.py" "$PKG_DIR/tools/" cp -f "$GITHUB_WORKSPACE/tools/esptool.py" "$PKG_DIR/tools/"
cp -f "$GITHUB_WORKSPACE/tools/gen_esp32part.py" "$PKG_DIR/tools/" cp -f "$GITHUB_WORKSPACE/tools/gen_esp32part.py" "$PKG_DIR/tools/"
cp -f "$GITHUB_WORKSPACE/tools/gen_esp32part.exe" "$PKG_DIR/tools/" cp -f "$GITHUB_WORKSPACE/tools/gen_esp32part.exe" "$PKG_DIR/tools/"
cp -Rf "$GITHUB_WORKSPACE/tools/partitions" "$PKG_DIR/tools/" cp -Rf "$GITHUB_WORKSPACE/tools/partitions" "$PKG_DIR/tools/"
cp -Rf "$GITHUB_WORKSPACE/tools/sdk" "$PKG_DIR/tools/" cp -Rf "$GITHUB_WORKSPACE/tools/sdk" "$PKG_DIR/tools/"
cp -f "$GITHUB_WORKSPACE/tools/platformio-build.py" "$PKG_DIR/tools/"
# Remove unnecessary files in the package folder # Remove unnecessary files in the package folder
echo "Cleaning up folders ..." echo "Cleaning up folders ..."

View File

@ -241,7 +241,6 @@ bool rmtLoop(rmt_obj_t* rmt, rmt_data_t* data, size_t size)
return false; return false;
} }
int channel = rmt->channel;
int allocated_size = MAX_DATA_PER_CHANNEL * rmt->buffers; int allocated_size = MAX_DATA_PER_CHANNEL * rmt->buffers;
if (size > allocated_size) { if (size > allocated_size) {

View File

@ -277,6 +277,16 @@ void AsyncUDPMessage::flush()
_index = 0; _index = 0;
} }
AsyncUDPPacket::AsyncUDPPacket(AsyncUDPPacket &packet){
_udp = packet._udp;
_pb = packet._pb;
_if = packet._if;
_data = packet._data;
_len = packet._len;
_index = 0;
pbuf_ref(_pb);
}
AsyncUDPPacket::AsyncUDPPacket(AsyncUDP *udp, pbuf *pb, const ip_addr_t *raddr, uint16_t rport, struct netif * ntif) AsyncUDPPacket::AsyncUDPPacket(AsyncUDP *udp, pbuf *pb, const ip_addr_t *raddr, uint16_t rport, struct netif * ntif)
{ {
@ -479,6 +489,7 @@ AsyncUDP::AsyncUDP()
{ {
_pcb = NULL; _pcb = NULL;
_connected = false; _connected = false;
_lastErr = ERR_OK;
_handler = NULL; _handler = NULL;
} }
@ -517,8 +528,8 @@ bool AsyncUDP::connect(const ip_addr_t *addr, uint16_t port)
} }
close(); close();
UDP_MUTEX_LOCK(); UDP_MUTEX_LOCK();
err_t err = _udp_connect(_pcb, addr, port); _lastErr = _udp_connect(_pcb, addr, port);
if(err != ERR_OK) { if(_lastErr != ERR_OK) {
UDP_MUTEX_UNLOCK(); UDP_MUTEX_UNLOCK();
return false; return false;
} }
@ -646,7 +657,7 @@ size_t AsyncUDP::writeTo(const uint8_t * data, size_t len, const ip_addr_t * add
if(len > CONFIG_TCP_MSS) { if(len > CONFIG_TCP_MSS) {
len = CONFIG_TCP_MSS; len = CONFIG_TCP_MSS;
} }
err_t err = ERR_OK; _lastErr = ERR_OK;
pbuf* pbt = pbuf_alloc(PBUF_TRANSPORT, len, PBUF_RAM); pbuf* pbt = pbuf_alloc(PBUF_TRANSPORT, len, PBUF_RAM);
if(pbt != NULL) { if(pbt != NULL) {
uint8_t* dst = reinterpret_cast<uint8_t*>(pbt->payload); uint8_t* dst = reinterpret_cast<uint8_t*>(pbt->payload);
@ -656,16 +667,16 @@ size_t AsyncUDP::writeTo(const uint8_t * data, size_t len, const ip_addr_t * add
void * nif = NULL; void * nif = NULL;
tcpip_adapter_get_netif((tcpip_adapter_if_t)tcpip_if, &nif); tcpip_adapter_get_netif((tcpip_adapter_if_t)tcpip_if, &nif);
if(!nif){ if(!nif){
err = _udp_sendto(_pcb, pbt, addr, port); _lastErr = _udp_sendto(_pcb, pbt, addr, port);
} else { } else {
err = _udp_sendto_if(_pcb, pbt, addr, port, (struct netif *)nif); _lastErr = _udp_sendto_if(_pcb, pbt, addr, port, (struct netif *)nif);
} }
} else { } else {
err = _udp_sendto(_pcb, pbt, addr, port); _lastErr = _udp_sendto(_pcb, pbt, addr, port);
} }
UDP_MUTEX_UNLOCK(); UDP_MUTEX_UNLOCK();
pbuf_free(pbt); pbuf_free(pbt);
if(err < ERR_OK) { if(_lastErr < ERR_OK) {
return 0; return 0;
} }
return len; return len;
@ -682,9 +693,8 @@ void AsyncUDP::_recv(udp_pcb *upcb, pbuf *pb, const ip_addr_t *addr, uint16_t po
if(_handler) { if(_handler) {
AsyncUDPPacket packet(this, this_pb, addr, port, netif); AsyncUDPPacket packet(this, this_pb, addr, port, netif);
_handler(packet); _handler(packet);
} else {
pbuf_free(this_pb);
} }
pbuf_free(this_pb);
} }
} }
@ -870,6 +880,10 @@ bool AsyncUDP::connected()
return _connected; return _connected;
} }
esp_err_t AsyncUDP::lastErr() {
return _lastErr;
}
void AsyncUDP::onPacket(AuPacketHandlerFunctionWithArg cb, void * arg) void AsyncUDP::onPacket(AuPacketHandlerFunctionWithArg cb, void * arg)
{ {
onPacket(std::bind(cb, arg, std::placeholders::_1)); onPacket(std::bind(cb, arg, std::placeholders::_1));

View File

@ -58,6 +58,7 @@ protected:
size_t _len; size_t _len;
size_t _index; size_t _index;
public: public:
AsyncUDPPacket(AsyncUDPPacket &packet);
AsyncUDPPacket(AsyncUDP *udp, pbuf *pb, const ip_addr_t *addr, uint16_t port, struct netif * netif); AsyncUDPPacket(AsyncUDP *udp, pbuf *pb, const ip_addr_t *addr, uint16_t port, struct netif * netif);
virtual ~AsyncUDPPacket(); virtual ~AsyncUDPPacket();
@ -95,6 +96,7 @@ protected:
udp_pcb *_pcb; udp_pcb *_pcb;
//xSemaphoreHandle _lock; //xSemaphoreHandle _lock;
bool _connected; bool _connected;
esp_err_t _lastErr;
AuPacketHandlerFunction _handler; AuPacketHandlerFunction _handler;
bool _init(); bool _init();
@ -144,6 +146,7 @@ public:
IPAddress listenIP(); IPAddress listenIP();
IPv6Address listenIPv6(); IPv6Address listenIPv6();
bool connected(); bool connected();
esp_err_t lastErr();
operator bool(); operator bool();
static void _s_recv(void *arg, udp_pcb *upcb, pbuf *p, const ip_addr_t *addr, uint16_t port, struct netif * netif); static void _s_recv(void *arg, udp_pcb *upcb, pbuf *p, const ip_addr_t *addr, uint16_t port, struct netif * netif);

View File

@ -25,6 +25,7 @@ BLEAdvertisedDevice::BLEAdvertisedDevice() {
m_manufacturerData = ""; m_manufacturerData = "";
m_name = ""; m_name = "";
m_rssi = -9999; m_rssi = -9999;
m_serviceUUIDs = {};
m_serviceData = {}; m_serviceData = {};
m_serviceDataUUIDs = {}; m_serviceDataUUIDs = {};
m_txPower = 0; m_txPower = 0;
@ -34,8 +35,6 @@ BLEAdvertisedDevice::BLEAdvertisedDevice() {
m_haveManufacturerData = false; m_haveManufacturerData = false;
m_haveName = false; m_haveName = false;
m_haveRSSI = false; m_haveRSSI = false;
m_haveServiceData = false;
m_haveServiceUUID = false;
m_haveTXPower = false; m_haveTXPower = false;
} // BLEAdvertisedDevice } // BLEAdvertisedDevice
@ -107,11 +106,7 @@ BLEScan* BLEAdvertisedDevice::getScan() {
* @return Number of service data discovered. * @return Number of service data discovered.
*/ */
int BLEAdvertisedDevice::getServiceDataCount() { int BLEAdvertisedDevice::getServiceDataCount() {
if (m_haveServiceData) return m_serviceData.size();
return m_serviceData.size();
else
return 0;
} //getServiceDataCount } //getServiceDataCount
/** /**
@ -119,7 +114,7 @@ int BLEAdvertisedDevice::getServiceDataCount() {
* @return The ServiceData of the advertised device. * @return The ServiceData of the advertised device.
*/ */
std::string BLEAdvertisedDevice::getServiceData() { std::string BLEAdvertisedDevice::getServiceData() {
return m_serviceData[0]; return m_serviceData.empty() ? std::string() : m_serviceData.front();
} //getServiceData } //getServiceData
/** /**
@ -130,12 +125,20 @@ std::string BLEAdvertisedDevice::getServiceData(int i) {
return m_serviceData[i]; return m_serviceData[i];
} //getServiceData } //getServiceData
/**
* @brief Get the number of service data UUIDs.
* @return Number of service data UUIDs discovered.
*/
int BLEAdvertisedDevice::getServiceDataUUIDCount() {
return m_serviceDataUUIDs.size();
} //getServiceDataUUIDCount
/** /**
* @brief Get the service data UUID. * @brief Get the service data UUID.
* @return The service data UUID. * @return The service data UUID.
*/ */
BLEUUID BLEAdvertisedDevice::getServiceDataUUID() { BLEUUID BLEAdvertisedDevice::getServiceDataUUID() {
return m_serviceDataUUIDs[0]; return m_serviceDataUUIDs.empty() ? BLEUUID() : m_serviceDataUUIDs.front();
} // getServiceDataUUID } // getServiceDataUUID
/** /**
@ -146,12 +149,20 @@ BLEUUID BLEAdvertisedDevice::getServiceDataUUID(int i) {
return m_serviceDataUUIDs[i]; return m_serviceDataUUIDs[i];
} // getServiceDataUUID } // getServiceDataUUID
/**
* @brief Get the number of service UUIDs.
* @return Number of service UUIDs discovered.
*/
int BLEAdvertisedDevice::getServiceUUIDCount() {
return m_serviceUUIDs.size();
} //getServiceUUIDCount
/** /**
* @brief Get the Service UUID. * @brief Get the Service UUID.
* @return The Service UUID of the advertised device. * @return The Service UUID of the advertised device.
*/ */
BLEUUID BLEAdvertisedDevice::getServiceUUID() { BLEUUID BLEAdvertisedDevice::getServiceUUID() {
return m_serviceUUIDs[0]; return m_serviceUUIDs.empty() ? BLEUUID() : m_serviceUUIDs.front();
} // getServiceUUID } // getServiceUUID
/** /**
@ -167,7 +178,7 @@ BLEUUID BLEAdvertisedDevice::getServiceUUID(int i) {
* @return Return true if service is advertised * @return Return true if service is advertised
*/ */
bool BLEAdvertisedDevice::isAdvertisingService(BLEUUID uuid){ bool BLEAdvertisedDevice::isAdvertisingService(BLEUUID uuid){
for (int i = 0; i < m_serviceUUIDs.size(); i++) { for (int i = 0; i < getServiceUUIDCount(); i++) {
if (m_serviceUUIDs[i].equals(uuid)) return true; if (m_serviceUUIDs[i].equals(uuid)) return true;
} }
return false; return false;
@ -224,7 +235,7 @@ bool BLEAdvertisedDevice::haveRSSI() {
* @return True if there is a service data value present. * @return True if there is a service data value present.
*/ */
bool BLEAdvertisedDevice::haveServiceData() { bool BLEAdvertisedDevice::haveServiceData() {
return m_haveServiceData; return !m_serviceData.empty();
} // haveServiceData } // haveServiceData
@ -233,7 +244,7 @@ bool BLEAdvertisedDevice::haveServiceData() {
* @return True if there is a service UUID value present. * @return True if there is a service UUID value present.
*/ */
bool BLEAdvertisedDevice::haveServiceUUID() { bool BLEAdvertisedDevice::haveServiceUUID() {
return m_haveServiceUUID; return !m_serviceUUIDs.empty();
} // haveServiceUUID } // haveServiceUUID
@ -486,7 +497,6 @@ void BLEAdvertisedDevice::setServiceUUID(const char* serviceUUID) {
*/ */
void BLEAdvertisedDevice::setServiceUUID(BLEUUID serviceUUID) { void BLEAdvertisedDevice::setServiceUUID(BLEUUID serviceUUID) {
m_serviceUUIDs.push_back(serviceUUID); m_serviceUUIDs.push_back(serviceUUID);
m_haveServiceUUID = true;
log_d("- addServiceUUID(): serviceUUID: %s", serviceUUID.toString().c_str()); log_d("- addServiceUUID(): serviceUUID: %s", serviceUUID.toString().c_str());
} // setServiceUUID } // setServiceUUID
@ -496,7 +506,6 @@ void BLEAdvertisedDevice::setServiceUUID(BLEUUID serviceUUID) {
* @param [in] data ServiceData value. * @param [in] data ServiceData value.
*/ */
void BLEAdvertisedDevice::setServiceData(std::string serviceData) { void BLEAdvertisedDevice::setServiceData(std::string serviceData) {
m_haveServiceData = true; // Set the flag that indicates we have service data.
m_serviceData.push_back(serviceData); // Save the service data that we received. m_serviceData.push_back(serviceData); // Save the service data that we received.
} //setServiceData } //setServiceData
@ -506,7 +515,6 @@ void BLEAdvertisedDevice::setServiceData(std::string serviceData) {
* @param [in] data ServiceDataUUID value. * @param [in] data ServiceDataUUID value.
*/ */
void BLEAdvertisedDevice::setServiceDataUUID(BLEUUID uuid) { void BLEAdvertisedDevice::setServiceDataUUID(BLEUUID uuid) {
m_haveServiceData = true; // Set the flag that indicates we have service data.
m_serviceDataUUIDs.push_back(uuid); m_serviceDataUUIDs.push_back(uuid);
log_d("- addServiceDataUUID(): serviceDataUUID: %s", uuid.toString().c_str()); log_d("- addServiceDataUUID(): serviceDataUUID: %s", uuid.toString().c_str());
} // setServiceDataUUID } // setServiceDataUUID
@ -542,7 +550,7 @@ std::string BLEAdvertisedDevice::toString() {
free(pHex); free(pHex);
} }
if (haveServiceUUID()) { if (haveServiceUUID()) {
for (int i=0; i < m_serviceUUIDs.size(); i++) { for (int i=0; i < getServiceUUIDCount(); i++) {
res += ", serviceUUID: " + getServiceUUID(i).toString(); res += ", serviceUUID: " + getServiceUUID(i).toString();
} }
} }

View File

@ -42,6 +42,8 @@ public:
BLEUUID getServiceUUID(); BLEUUID getServiceUUID();
BLEUUID getServiceUUID(int i); BLEUUID getServiceUUID(int i);
int getServiceDataCount(); int getServiceDataCount();
int getServiceDataUUIDCount();
int getServiceUUIDCount();
int8_t getTXPower(); int8_t getTXPower();
uint8_t* getPayload(); uint8_t* getPayload();
size_t getPayloadLength(); size_t getPayloadLength();
@ -83,8 +85,6 @@ private:
bool m_haveManufacturerData; bool m_haveManufacturerData;
bool m_haveName; bool m_haveName;
bool m_haveRSSI; bool m_haveRSSI;
bool m_haveServiceData;
bool m_haveServiceUUID;
bool m_haveTXPower; bool m_haveTXPower;

View File

@ -60,6 +60,7 @@ BLEClient::~BLEClient() {
delete myPair.second; delete myPair.second;
} }
m_servicesMap.clear(); m_servicesMap.clear();
m_servicesMapByInstID.clear();
} // ~BLEClient } // ~BLEClient
@ -109,7 +110,17 @@ bool BLEClient::connect(BLEAddress address, esp_ble_addr_type_t type) {
return false; return false;
} }
m_semaphoreRegEvt.wait("connect"); uint32_t rc = m_semaphoreRegEvt.wait("connect");
if (rc != ESP_GATT_OK) {
// fixes ESP_GATT_NO_RESOURCES error mostly
log_e("esp_ble_gattc_app_register_error: rc=%d", rc);
BLEDevice::removePeerDevice(m_appId, true);
// not sure if this is needed here
// esp_ble_gattc_app_unregister(m_gattc_if);
// m_gattc_if = ESP_GATT_IF_NONE;
return false;
}
m_peerAddress = address; m_peerAddress = address;
@ -127,7 +138,13 @@ bool BLEClient::connect(BLEAddress address, esp_ble_addr_type_t type) {
return false; return false;
} }
uint32_t rc = m_semaphoreOpenEvt.wait("connect"); // Wait for the connection to complete. rc = m_semaphoreOpenEvt.wait("connect"); // Wait for the connection to complete.
// check the status of the connection and cleanup in case of failure
if (rc != ESP_GATT_OK) {
BLEDevice::removePeerDevice(m_appId, true);
esp_ble_gattc_app_unregister(m_gattc_if);
m_gattc_if = ESP_GATT_IF_NONE;
}
log_v("<< connect(), rc=%d", rc==ESP_GATT_OK); log_v("<< connect(), rc=%d", rc==ESP_GATT_OK);
return rc == ESP_GATT_OK; return rc == ESP_GATT_OK;
} // connect } // connect
@ -159,6 +176,11 @@ void BLEClient::gattClientEventHandler(
log_d("gattClientEventHandler [esp_gatt_if: %d] ... %s", log_d("gattClientEventHandler [esp_gatt_if: %d] ... %s",
gattc_if, BLEUtils::gattClientEventTypeToString(event).c_str()); gattc_if, BLEUtils::gattClientEventTypeToString(event).c_str());
// it is possible to receive events from other connections while waiting for registration
if (m_gattc_if == ESP_GATT_IF_NONE && event != ESP_GATTC_REG_EVT) {
return;
}
// Execute handler code based on the type of event received. // Execute handler code based on the type of event received.
switch(event) { switch(event) {
@ -183,15 +205,17 @@ void BLEClient::gattClientEventHandler(
if (evtParam->disconnect.conn_id != getConnId()) break; if (evtParam->disconnect.conn_id != getConnId()) break;
// If we receive a disconnect event, set the class flag that indicates that we are // If we receive a disconnect event, set the class flag that indicates that we are
// no longer connected. // no longer connected.
if (m_isConnected && m_pClientCallbacks != nullptr) { bool m_wasConnected = m_isConnected;
m_pClientCallbacks->onDisconnect(this);
}
m_isConnected = false; m_isConnected = false;
esp_ble_gattc_app_unregister(m_gattc_if); esp_ble_gattc_app_unregister(m_gattc_if);
m_gattc_if = ESP_GATT_IF_NONE;
m_semaphoreOpenEvt.give(ESP_GATT_IF_NONE); m_semaphoreOpenEvt.give(ESP_GATT_IF_NONE);
m_semaphoreRssiCmplEvt.give(); m_semaphoreRssiCmplEvt.give();
m_semaphoreSearchCmplEvt.give(1); m_semaphoreSearchCmplEvt.give(1);
BLEDevice::removePeerDevice(m_appId, true); BLEDevice::removePeerDevice(m_appId, true);
if (m_wasConnected && m_pClientCallbacks != nullptr) {
m_pClientCallbacks->onDisconnect(this);
}
break; break;
} // ESP_GATTC_DISCONNECT_EVT } // ESP_GATTC_DISCONNECT_EVT
@ -227,7 +251,8 @@ void BLEClient::gattClientEventHandler(
// //
case ESP_GATTC_REG_EVT: { case ESP_GATTC_REG_EVT: {
m_gattc_if = gattc_if; m_gattc_if = gattc_if;
m_semaphoreRegEvt.give(); // pass on the registration status result, in case of failure
m_semaphoreRegEvt.give(evtParam->reg.status);
break; break;
} // ESP_GATTC_REG_EVT } // ESP_GATTC_REG_EVT

View File

@ -52,6 +52,7 @@ BLERemoteCharacteristic::BLERemoteCharacteristic(
*/ */
BLERemoteCharacteristic::~BLERemoteCharacteristic() { BLERemoteCharacteristic::~BLERemoteCharacteristic() {
removeDescriptors(); // Release resources for any descriptor information we may have allocated. removeDescriptors(); // Release resources for any descriptor information we may have allocated.
free(m_rawData);
} // ~BLERemoteCharacteristic } // ~BLERemoteCharacteristic

View File

@ -39,6 +39,7 @@ public:
bool canWriteNoResponse(); bool canWriteNoResponse();
BLERemoteDescriptor* getDescriptor(BLEUUID uuid); BLERemoteDescriptor* getDescriptor(BLEUUID uuid);
std::map<std::string, BLERemoteDescriptor*>* getDescriptors(); std::map<std::string, BLERemoteDescriptor*>* getDescriptors();
BLERemoteService* getRemoteService();
uint16_t getHandle(); uint16_t getHandle();
BLEUUID getUUID(); BLEUUID getUUID();
std::string readValue(); std::string readValue();
@ -63,7 +64,6 @@ private:
// Private member functions // Private member functions
void gattClientEventHandler(esp_gattc_cb_event_t event, esp_gatt_if_t gattc_if, esp_ble_gattc_cb_param_t* evtParam); void gattClientEventHandler(esp_gattc_cb_event_t event, esp_gatt_if_t gattc_if, esp_ble_gattc_cb_param_t* evtParam);
BLERemoteService* getRemoteService();
void removeDescriptors(); void removeDescriptors();
void retrieveDescriptors(); void retrieveDescriptors();

View File

@ -84,7 +84,7 @@ public:
void enableArduino(uint16_t port=3232, bool auth=false); void enableArduino(uint16_t port=3232, bool auth=false);
void disableArduino(); void disableArduino();
void enableWorkstation(wifi_interface_t interface=ESP_IF_WIFI_STA); void enableWorkstation(wifi_interface_t interface=WIFI_IF_STA);
void disableWorkstation(); void disableWorkstation();
IPAddress queryHost(char *host, uint32_t timeout=2000); IPAddress queryHost(char *host, uint32_t timeout=2000);

View File

@ -269,13 +269,20 @@ bool HTTPClient::beginInternal(String url, const char* expectedProtocol)
// get port // get port
index = host.indexOf(':'); index = host.indexOf(':');
String the_host;
if(index >= 0) { if(index >= 0) {
_host = host.substring(0, index); // hostname the_host = host.substring(0, index); // hostname
host.remove(0, (index + 1)); // remove hostname + : host.remove(0, (index + 1)); // remove hostname + :
_port = host.toInt(); // get port _port = host.toInt(); // get port
} else { } else {
_host = host; the_host = host;
} }
if(_host != the_host && connected()){
log_d("switching host from '%s' to '%s'. disconnecting first", _host.c_str(), the_host.c_str());
_canReuse = false;
disconnect(true);
}
_host = the_host;
_uri = url; _uri = url;
log_d("host: %s port: %d url: %s", _host.c_str(), _port, _uri.c_str()); log_d("host: %s port: %d url: %s", _host.c_str(), _port, _uri.c_str());
return true; return true;
@ -1318,9 +1325,9 @@ int HTTPClient::writeToStreamDataBlock(Stream * stream, int size)
readBytes = buff_size; readBytes = buff_size;
} }
// stop if no more reading // stop if no more reading
if (readBytes == 0) if (readBytes == 0)
break; break;
// read data // read data
int bytesRead = _client->readBytes(buff, readBytes); int bytesRead = _client->readBytes(buff, readBytes);

View File

@ -14,6 +14,7 @@
#include "Preferences.h" #include "Preferences.h"
#include "nvs.h" #include "nvs.h"
#include "nvs_flash.h"
const char * nvs_errors[] = { "OTHER", "NOT_INITIALIZED", "NOT_FOUND", "TYPE_MISMATCH", "READ_ONLY", "NOT_ENOUGH_SPACE", "INVALID_NAME", "INVALID_HANDLE", "REMOVE_FAILED", "KEY_TOO_LONG", "PAGE_FULL", "INVALID_STATE", "INVALID_LENGTH"}; const char * nvs_errors[] = { "OTHER", "NOT_INITIALIZED", "NOT_FOUND", "TYPE_MISMATCH", "READ_ONLY", "NOT_ENOUGH_SPACE", "INVALID_NAME", "INVALID_HANDLE", "REMOVE_FAILED", "KEY_TOO_LONG", "PAGE_FULL", "INVALID_STATE", "INVALID_LENGTH"};
#define nvs_error(e) (((e)>ESP_ERR_NVS_BASE)?nvs_errors[(e)&~(ESP_ERR_NVS_BASE)]:nvs_errors[0]) #define nvs_error(e) (((e)>ESP_ERR_NVS_BASE)?nvs_errors[(e)&~(ESP_ERR_NVS_BASE)]:nvs_errors[0])
@ -28,12 +29,22 @@ Preferences::~Preferences(){
end(); end();
} }
bool Preferences::begin(const char * name, bool readOnly){ bool Preferences::begin(const char * name, bool readOnly, const char* partition_label){
if(_started){ if(_started){
return false; return false;
} }
_readOnly = readOnly; _readOnly = readOnly;
esp_err_t err = nvs_open(name, readOnly?NVS_READONLY:NVS_READWRITE, &_handle); esp_err_t err = ESP_OK;
if (partition_label != NULL) {
err = nvs_flash_init_partition(partition_label);
if (err) {
log_e("nvs_flash_init_partition failed: %s", nvs_error(err));
return false;
}
err = nvs_open_from_partition(partition_label, name, readOnly ? NVS_READONLY : NVS_READWRITE, &_handle);
} else {
err = nvs_open(name, readOnly?NVS_READONLY:NVS_READWRITE, &_handle);
}
if(err){ if(err){
log_e("nvs_open failed: %s", nvs_error(err)); log_e("nvs_open failed: %s", nvs_error(err));
return false; return false;

View File

@ -29,7 +29,7 @@ class Preferences {
Preferences(); Preferences();
~Preferences(); ~Preferences();
bool begin(const char * name, bool readOnly=false); bool begin(const char * name, bool readOnly=false, const char* partition_label=NULL);
void end(); void end();
bool clear(); bool clear();

View File

@ -303,7 +303,6 @@ void WebServer::_uploadWriteByte(uint8_t b){
} }
int WebServer::_uploadReadByte(WiFiClient& client){ int WebServer::_uploadReadByte(WiFiClient& client){
if (!client.connected()) return -1;
int res = client.read(); int res = client.read();
if(res < 0) { if(res < 0) {
// keep trying until you either read a valid byte or timeout // keep trying until you either read a valid byte or timeout
@ -311,6 +310,7 @@ int WebServer::_uploadReadByte(WiFiClient& client){
long timeoutIntervalMillis = client.getTimeout(); long timeoutIntervalMillis = client.getTimeout();
boolean timedOut = false; boolean timedOut = false;
for(;;) { for(;;) {
if (!client.connected()) return -1;
// loosely modeled after blinkWithoutDelay pattern // loosely modeled after blinkWithoutDelay pattern
while(!timedOut && !client.available() && client.connected()){ while(!timedOut && !client.available() && client.connected()){
delay(2); delay(2);

View File

@ -412,6 +412,8 @@ void WebServer::_prepareHeader(String& response, int code, const char* content_t
} }
if (_corsEnabled) { if (_corsEnabled) {
sendHeader(String(FPSTR("Access-Control-Allow-Origin")), String("*")); sendHeader(String(FPSTR("Access-Control-Allow-Origin")), String("*"));
sendHeader(String(FPSTR("Access-Control-Allow-Methods")), String("*"));
sendHeader(String(FPSTR("Access-Control-Allow-Headers")), String("*"));
} }
sendHeader(String(F("Connection")), String(F("close"))); sendHeader(String(F("Connection")), String(F("close")));

View File

@ -379,6 +379,7 @@ esp_err_t WiFiGenericClass::_eventCallback(void *arg, system_event_t *event, wif
} else if(event->event_id == SYSTEM_EVENT_STA_START) { } else if(event->event_id == SYSTEM_EVENT_STA_START) {
WiFiSTAClass::_setStatus(WL_DISCONNECTED); WiFiSTAClass::_setStatus(WL_DISCONNECTED);
setStatusBits(STA_STARTED_BIT); setStatusBits(STA_STARTED_BIT);
tcpip_adapter_set_hostname(TCPIP_ADAPTER_IF_STA, WiFiSTAClass::_hostname.c_str());
} else if(event->event_id == SYSTEM_EVENT_STA_STOP) { } else if(event->event_id == SYSTEM_EVENT_STA_STOP) {
WiFiSTAClass::_setStatus(WL_NO_SHIELD); WiFiSTAClass::_setStatus(WL_NO_SHIELD);
clearStatusBits(STA_STARTED_BIT | STA_CONNECTED_BIT | STA_HAS_IP_BIT | STA_HAS_IP6_BIT); clearStatusBits(STA_STARTED_BIT | STA_CONNECTED_BIT | STA_HAS_IP_BIT | STA_HAS_IP6_BIT);

View File

@ -71,6 +71,7 @@ static bool sta_config_equal(const wifi_config_t& lhs, const wifi_config_t& rhs)
bool WiFiSTAClass::_autoReconnect = true; bool WiFiSTAClass::_autoReconnect = true;
bool WiFiSTAClass::_useStaticIp = false; bool WiFiSTAClass::_useStaticIp = false;
String WiFiSTAClass::_hostname = "esp32-arduino";
static wl_status_t _sta_status = WL_NO_SHIELD; static wl_status_t _sta_status = WL_NO_SHIELD;
static EventGroupHandle_t _sta_status_group = NULL; static EventGroupHandle_t _sta_status_group = NULL;
@ -284,7 +285,7 @@ bool WiFiSTAClass::config(IPAddress local_ip, IPAddress gateway, IPAddress subne
tcpip_adapter_ip_info_t info; tcpip_adapter_ip_info_t info;
if(local_ip != (uint32_t)0x00000000){ if(local_ip != (uint32_t)0x00000000 && local_ip != INADDR_NONE){
info.ip.addr = static_cast<uint32_t>(local_ip); info.ip.addr = static_cast<uint32_t>(local_ip);
info.gw.addr = static_cast<uint32_t>(gateway); info.gw.addr = static_cast<uint32_t>(gateway);
info.netmask.addr = static_cast<uint32_t>(subnet); info.netmask.addr = static_cast<uint32_t>(subnet);
@ -320,13 +321,13 @@ bool WiFiSTAClass::config(IPAddress local_ip, IPAddress gateway, IPAddress subne
ip_addr_t d; ip_addr_t d;
d.type = IPADDR_TYPE_V4; d.type = IPADDR_TYPE_V4;
if(dns1 != (uint32_t)0x00000000) { if(dns1 != (uint32_t)0x00000000 && dns1 != INADDR_NONE) {
// Set DNS1-Server // Set DNS1-Server
d.u_addr.ip4.addr = static_cast<uint32_t>(dns1); d.u_addr.ip4.addr = static_cast<uint32_t>(dns1);
dns_setserver(0, &d); dns_setserver(0, &d);
} }
if(dns2 != (uint32_t)0x00000000) { if(dns2 != (uint32_t)0x00000000 && dns2 != INADDR_NONE) {
// Set DNS2-Server // Set DNS2-Server
d.u_addr.ip4.addr = static_cast<uint32_t>(dns2); d.u_addr.ip4.addr = static_cast<uint32_t>(dns2);
dns_setserver(1, &d); dns_setserver(1, &d);
@ -636,6 +637,7 @@ const char * WiFiSTAClass::getHostname()
*/ */
bool WiFiSTAClass::setHostname(const char * hostname) bool WiFiSTAClass::setHostname(const char * hostname)
{ {
_hostname = hostname;
if(WiFiGenericClass::getMode() == WIFI_MODE_NULL){ if(WiFiGenericClass::getMode() == WIFI_MODE_NULL){
return false; return false;
} }

View File

@ -86,6 +86,7 @@ public:
int8_t RSSI(); int8_t RSSI();
static void _setStatus(wl_status_t status); static void _setStatus(wl_status_t status);
static String _hostname;
protected: protected:
static bool _useStaticIp; static bool _useStaticIp;
static bool _autoReconnect; static bool _autoReconnect;

View File

@ -193,6 +193,13 @@
"archiveFileName": "mkspiffs-0.2.3-arduino-esp32-linux-armhf.tar.gz", "archiveFileName": "mkspiffs-0.2.3-arduino-esp32-linux-armhf.tar.gz",
"checksum": "SHA-256:ade3dc00117912ac08a1bdbfbfe76b12d21a34bc5fa1de0cfc45fe7a8d0a0185", "checksum": "SHA-256:ade3dc00117912ac08a1bdbfbfe76b12d21a34bc5fa1de0cfc45fe7a8d0a0185",
"size": "40665" "size": "40665"
},
{
"host": "aarch64-linux-gnu",
"url": "https://github.com/igrr/mkspiffs/releases/download/0.2.3/mkspiffs-0.2.3-arduino-esp32-linux-armhf.tar.gz",
"archiveFileName": "mkspiffs-0.2.3-arduino-esp32-linux-armhf.tar.gz",
"checksum": "SHA-256:ade3dc00117912ac08a1bdbfbfe76b12d21a34bc5fa1de0cfc45fe7a8d0a0185",
"size": "40665"
} }
] ]
} }

View File

@ -35,7 +35,7 @@ compiler.S.flags=-c -g3 -x assembler-with-cpp -MMD -mlongcalls
compiler.c.elf.cmd=xtensa-esp32-elf-gcc compiler.c.elf.cmd=xtensa-esp32-elf-gcc
compiler.c.elf.flags=-nostdlib "-L{compiler.sdk.path}/lib" "-L{compiler.sdk.path}/ld" -T esp32_out.ld -T esp32.project.ld -T esp32.rom.ld -T esp32.peripherals.ld -T esp32.rom.libgcc.ld -T esp32.rom.spiram_incompatible_fns.ld -u ld_include_panic_highint_hdl -u call_user_start_cpu0 -Wl,--gc-sections -Wl,-static -Wl,--undefined=uxTopUsedPriority -u __cxa_guard_dummy -u __cxx_fatal_exception compiler.c.elf.flags=-nostdlib "-L{compiler.sdk.path}/lib" "-L{compiler.sdk.path}/ld" -T esp32_out.ld -T esp32.project.ld -T esp32.rom.ld -T esp32.peripherals.ld -T esp32.rom.libgcc.ld -T esp32.rom.spiram_incompatible_fns.ld -u ld_include_panic_highint_hdl -u call_user_start_cpu0 -Wl,--gc-sections -Wl,-static -Wl,--undefined=uxTopUsedPriority -u __cxa_guard_dummy -u __cxx_fatal_exception
compiler.c.elf.libs=-lgcc -lesp_http_client -lcxx -lwps -lsoc -lesp_event -lc -lprotobuf-c -lunity -lesp_ringbuf -lasio -lnewlib -lfreemodbus -lbtdm_app -ltcpip_adapter -llog -lxtensa-debug-module -lsmartconfig -lspi_flash -lmesh -lwpa -lheap -lbootloader_support -lapp_update -llwip -ldetection_cat_face -lopenssl -ldriver -lesp_https_ota -lfr -lconsole -llibsodium -lmqtt -ljson -lwear_levelling -lface_recognition -lfatfs -lspiffs -ldl -lrtc -ljsmn -lesp_http_server -lfreertos -lespcoredump -lesp_websocket_client -lod -lprotocomm -lwpa2 -lesp_adc_cal -lnghttp -lc_nano -lpp -lpe -lethernet -lbt -ldetection -lulp -lcoap -lfd -lespnow -lmdns -lmicro-ecc -lcore -lmbedtls -lcoexist -lface_detection -lesp32 -ltcp_transport -lphy -lsmartconfig_ack -lhal -lnvs_flash -lfb_gfx -lvfs -lesp32-camera -lm -lsdmmc -lapp_trace -lefuse -lnet80211 -lesp-tls -lwifi_provisioning -lwpa_supplicant -lesp_https_server -limage_util -lpthread -lexpat -lstdc++ compiler.c.elf.libs=-lgcc -lopenssl -lbtdm_app -lfatfs -lwps -lcoexist -lwear_levelling -lesp_http_client -lprotobuf-c -lhal -lnewlib -ldriver -lbootloader_support -lpp -lfreemodbus -lmesh -lsmartconfig -ljsmn -lwpa -lethernet -lphy -lapp_trace -lconsole -lulp -lwpa_supplicant -lfreertos -lbt -lmicro-ecc -lesp32-camera -lcxx -lxtensa-debug-module -ltcp_transport -lod -lmdns -ldetection -lvfs -lpe -lesp_websocket_client -lespcoredump -lesp_ringbuf -lsoc -lcore -lfb_gfx -lsdmmc -llibsodium -lcoap -ltcpip_adapter -lprotocomm -lesp_event -limage_util -lc_nano -lesp-tls -lasio -lrtc -lspi_flash -lwpa2 -lwifi_provisioning -lesp32 -lface_recognition -lapp_update -lnghttp -ldl -lspiffs -lface_detection -lefuse -lunity -lesp_https_server -lespnow -lnvs_flash -lesp_adc_cal -llog -ldetection_cat_face -lsmartconfig_ack -lexpat -lm -lfr -lmqtt -lc -lheap -lmbedtls -llwip -lnet80211 -lesp_http_server -lpthread -ljson -lesp_https_ota -lfd -lstdc++
compiler.as.cmd=xtensa-esp32-elf-as compiler.as.cmd=xtensa-esp32-elf-as

View File

@ -171,7 +171,7 @@ env.Append(
], ],
LIBS=[ LIBS=[
"-lgcc", "-lesp_http_client", "-lcxx", "-lwps", "-lsoc", "-lesp_event", "-lc", "-lprotobuf-c", "-lunity", "-lesp_ringbuf", "-lasio", "-lnewlib", "-lfreemodbus", "-lbtdm_app", "-ltcpip_adapter", "-llog", "-lxtensa-debug-module", "-lsmartconfig", "-lspi_flash", "-lmesh", "-lwpa", "-lheap", "-lbootloader_support", "-lapp_update", "-llwip", "-ldetection_cat_face", "-lopenssl", "-ldriver", "-lesp_https_ota", "-lfr", "-lconsole", "-llibsodium", "-lmqtt", "-ljson", "-lwear_levelling", "-lface_recognition", "-lfatfs", "-lspiffs", "-ldl", "-lrtc", "-ljsmn", "-lesp_http_server", "-lfreertos", "-lespcoredump", "-lesp_websocket_client", "-lod", "-lprotocomm", "-lwpa2", "-lesp_adc_cal", "-lnghttp", "-lc_nano", "-lpp", "-lpe", "-lethernet", "-lbt", "-ldetection", "-lulp", "-lcoap", "-lfd", "-lespnow", "-lmdns", "-lmicro-ecc", "-lcore", "-lmbedtls", "-lcoexist", "-lface_detection", "-lesp32", "-ltcp_transport", "-lphy", "-lsmartconfig_ack", "-lhal", "-lnvs_flash", "-lfb_gfx", "-lvfs", "-lesp32-camera", "-lm", "-lsdmmc", "-lapp_trace", "-lefuse", "-lnet80211", "-lesp-tls", "-lwifi_provisioning", "-lwpa_supplicant", "-lesp_https_server", "-limage_util", "-lpthread", "-lexpat", "-lstdc++" "-lgcc", "-lopenssl", "-lbtdm_app", "-lfatfs", "-lwps", "-lcoexist", "-lwear_levelling", "-lesp_http_client", "-lprotobuf-c", "-lhal", "-lnewlib", "-ldriver", "-lbootloader_support", "-lpp", "-lfreemodbus", "-lmesh", "-lsmartconfig", "-ljsmn", "-lwpa", "-lethernet", "-lphy", "-lapp_trace", "-lconsole", "-lulp", "-lwpa_supplicant", "-lfreertos", "-lbt", "-lmicro-ecc", "-lesp32-camera", "-lcxx", "-lxtensa-debug-module", "-ltcp_transport", "-lod", "-lmdns", "-ldetection", "-lvfs", "-lpe", "-lesp_websocket_client", "-lespcoredump", "-lesp_ringbuf", "-lsoc", "-lcore", "-lfb_gfx", "-lsdmmc", "-llibsodium", "-lcoap", "-ltcpip_adapter", "-lprotocomm", "-lesp_event", "-limage_util", "-lc_nano", "-lesp-tls", "-lasio", "-lrtc", "-lspi_flash", "-lwpa2", "-lwifi_provisioning", "-lesp32", "-lface_recognition", "-lapp_update", "-lnghttp", "-ldl", "-lspiffs", "-lface_detection", "-lefuse", "-lunity", "-lesp_https_server", "-lespnow", "-lnvs_flash", "-lesp_adc_cal", "-llog", "-ldetection_cat_face", "-lsmartconfig_ack", "-lexpat", "-lm", "-lfr", "-lmqtt", "-lc", "-lheap", "-lmbedtls", "-llwip", "-lnet80211", "-lesp_http_server", "-lpthread", "-ljson", "-lesp_https_ota", "-lfd", "-lstdc++"
], ],
LIBSOURCE_DIRS=[ LIBSOURCE_DIRS=[
@ -224,7 +224,9 @@ env.Prepend(LIBS=libs)
# #
fwpartitions_dir = join(FRAMEWORK_DIR, "tools", "partitions") fwpartitions_dir = join(FRAMEWORK_DIR, "tools", "partitions")
partitions_csv = env.BoardConfig().get("build.partitions", "default.csv") partitions_csv = env.BoardConfig().get("build.arduino.partitions", "default.csv")
if "build.partitions" in env.BoardConfig():
partitions_csv = env.BoardConfig().get("build.partitions")
env.Replace( env.Replace(
PARTITIONS_TABLE_CSV=abspath( PARTITIONS_TABLE_CSV=abspath(
join(fwpartitions_dir, partitions_csv) if isfile( join(fwpartitions_dir, partitions_csv) if isfile(

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@ -331,6 +331,12 @@ esp_err_t esp_bt_controller_disable(void);
*/ */
esp_bt_controller_status_t esp_bt_controller_get_status(void); esp_bt_controller_status_t esp_bt_controller_get_status(void);
/**
* @brief Get BT MAC address.
* @return Array pointer of length 6 storing MAC address value.
*/
uint8_t* esp_bt_get_mac(void);
/** @brief esp_vhci_host_callback /** @brief esp_vhci_host_callback
* used for vhci call host function to notify what host need to do * used for vhci call host function to notify what host need to do
*/ */

View File

@ -396,5 +396,5 @@
#define CONFIG_BTDM_MODEM_SLEEP_MODE_ORIG 1 #define CONFIG_BTDM_MODEM_SLEEP_MODE_ORIG 1
#define CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_ERROR 1 #define CONFIG_ARDUHAL_LOG_DEFAULT_LEVEL_ERROR 1
#define CONFIG_FATFS_API_ENCODING_ANSI_OEM 1 #define CONFIG_FATFS_API_ENCODING_ANSI_OEM 1
#define CONFIG_ARDUINO_IDF_COMMIT "cd59d107b" #define CONFIG_ARDUINO_IDF_COMMIT "d8082b7f3"
#define CONFIG_ARDUINO_IDF_BRANCH "release/v3.3" #define CONFIG_ARDUINO_IDF_BRANCH "release/v3.3"

View File

@ -244,6 +244,13 @@ esp_err_t esp_modem_sleep_deregister(modem_sleep_module_t module);
* microsecond since boot when phy/rf was last switched on * microsecond since boot when phy/rf was last switched on
*/ */
int64_t esp_phy_rf_get_on_ts(void); int64_t esp_phy_rf_get_on_ts(void);
/**
* @brief Get PHY lib version
* @return PHY lib version.
*/
char * get_phy_version_str(void);
#ifdef __cplusplus #ifdef __cplusplus
} }
#endif #endif

View File

@ -442,6 +442,8 @@ esp_err_t esp_wifi_scan_get_ap_records(uint16_t *number, wifi_ap_record_t *ap_re
/** /**
* @brief Get information of AP which the ESP32 station is associated with * @brief Get information of AP which the ESP32 station is associated with
* *
* @attention When the obtained country information is empty, it means that the AP does not carry country information
*
* @param ap_info the wifi_ap_record_t to hold AP information * @param ap_info the wifi_ap_record_t to hold AP information
* sta can get the connected ap's phy mode info through the struct member * sta can get the connected ap's phy mode info through the struct member
* phy_11bphy_11gphy_11nphy_lr in the wifi_ap_record_t struct. * phy_11bphy_11gphy_11nphy_lr in the wifi_ap_record_t struct.
@ -905,9 +907,9 @@ esp_err_t esp_wifi_set_vendor_ie_cb(esp_vendor_ie_cb_t cb, void *ctx);
* @attention 1. Maximum power before wifi startup is limited by PHY init data bin. * @attention 1. Maximum power before wifi startup is limited by PHY init data bin.
* @attention 2. The value set by this API will be mapped to the max_tx_power of the structure wifi_country_t variable. * @attention 2. The value set by this API will be mapped to the max_tx_power of the structure wifi_country_t variable.
* @attention 3. Mapping Table {Power, max_tx_power} = {{8, 2}, {20, 5}, {28, 7}, {34, 8}, {44, 11}, * @attention 3. Mapping Table {Power, max_tx_power} = {{8, 2}, {20, 5}, {28, 7}, {34, 8}, {44, 11},
* {52, 13}, {56, 14}, {60, 15}, {66, 16}, {72, 18}, {78, 20}}. * {52, 13}, {56, 14}, {60, 15}, {66, 16}, {72, 18}, {80, 20}}.
* @attention 4. Param power unit is 0.25dBm, range is [8, 78] corresponding to 2dBm - 20dBm. * @attention 4. Param power unit is 0.25dBm, range is [8, 84] corresponding to 2dBm - 20dBm.
* @attention 5. Relationship between set value and actual value. As follows: {set value range, actual value} = {{[8, 19],8}, {[20, 27],20}, {[28, 33],28}, {[34, 43],34}, {[44, 51],44}, {[52, 55],52}, {[56, 59],56}, {[60, 65],60}, {[66, 71],66}, {[72, 77],72}, {78,78}} * @attention 5. Relationship between set value and actual value. As follows: {set value range, actual value} = {{[8, 19],8}, {[20, 27],20}, {[28, 33],28}, {[34, 43],34}, {[44, 51],44}, {[52, 55],52}, {[56, 59],56}, {[60, 65],60}, {[66, 71],66}, {[72, 79],72}, {[80, 84],80}}.
* *
* @param power Maximum WiFi transmitting power. * @param power Maximum WiFi transmitting power.
* *

View File

@ -33,10 +33,10 @@ typedef enum {
WIFI_MODE_MAX WIFI_MODE_MAX
} wifi_mode_t; } wifi_mode_t;
typedef esp_interface_t wifi_interface_t; typedef enum {
WIFI_IF_STA = ESP_IF_WIFI_STA,
#define WIFI_IF_STA ESP_IF_WIFI_STA WIFI_IF_AP = ESP_IF_WIFI_AP,
#define WIFI_IF_AP ESP_IF_WIFI_AP } wifi_interface_t;
typedef enum { typedef enum {
WIFI_COUNTRY_POLICY_AUTO, /**< Country policy is auto, use the country info of AP to which the station is connected */ WIFI_COUNTRY_POLICY_AUTO, /**< Country policy is auto, use the country info of AP to which the station is connected */
@ -364,6 +364,7 @@ typedef enum {
#define WIFI_PROMIS_FILTER_MASK_MISC (1<<3) /**< filter the packets with type of WIFI_PKT_MISC */ #define WIFI_PROMIS_FILTER_MASK_MISC (1<<3) /**< filter the packets with type of WIFI_PKT_MISC */
#define WIFI_PROMIS_FILTER_MASK_DATA_MPDU (1<<4) /**< filter the MPDU which is a kind of WIFI_PKT_DATA */ #define WIFI_PROMIS_FILTER_MASK_DATA_MPDU (1<<4) /**< filter the MPDU which is a kind of WIFI_PKT_DATA */
#define WIFI_PROMIS_FILTER_MASK_DATA_AMPDU (1<<5) /**< filter the AMPDU which is a kind of WIFI_PKT_DATA */ #define WIFI_PROMIS_FILTER_MASK_DATA_AMPDU (1<<5) /**< filter the AMPDU which is a kind of WIFI_PKT_DATA */
#define WIFI_PROMIS_FILTER_MASK_FCSFAIL (1<<6) /**< filter the FCS failed packets, do not open it in general */
#define WIFI_PROMIS_CTRL_FILTER_MASK_ALL (0xFF800000) /**< filter all control packets */ #define WIFI_PROMIS_CTRL_FILTER_MASK_ALL (0xFF800000) /**< filter all control packets */
#define WIFI_PROMIS_CTRL_FILTER_MASK_WRAPPER (1<<23) /**< filter the control packets with subtype of Control Wrapper */ #define WIFI_PROMIS_CTRL_FILTER_MASK_WRAPPER (1<<23) /**< filter the control packets with subtype of Control Wrapper */

File diff suppressed because one or more lines are too long

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Binary file not shown.

Some files were not shown because too many files have changed in this diff Show More