diff --git a/.gitignore b/.gitignore index e0d6732..5107514 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,4 @@ git-version.h *.bin *.elf *.log +romfs_files.h diff --git a/RemoteIDModule/BLE_TX.cpp b/RemoteIDModule/BLE_TX.cpp index 2ee474c..1cba73d 100644 --- a/RemoteIDModule/BLE_TX.cpp +++ b/RemoteIDModule/BLE_TX.cpp @@ -68,6 +68,10 @@ static BLEMultiAdvertising advert(3); bool BLE_TX::init(void) { + if (initialised) { + return true; + } + initialised = true; BLEDevice::init(""); // generate random mac address @@ -102,6 +106,8 @@ bool BLE_TX::init(void) bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data) { + init(); + //set BLE name uint8_t legacy_name_payload[36]; char legacy_name[28] {}; @@ -125,6 +131,7 @@ bool BLE_TX::transmit_legacy_name(ODID_UAS_Data &UAS_data) bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data) { + init(); // create a packed UAS data message uint8_t payload[250]; int length = odid_message_build_pack(&UAS_data, payload, 255); @@ -153,6 +160,7 @@ bool BLE_TX::transmit_longrange(ODID_UAS_Data &UAS_data) bool BLE_TX::transmit_legacy(ODID_UAS_Data &UAS_data) { + init(); static uint8_t legacy_phase = 0; int legacy_length = 0; // setup ASTM header diff --git a/RemoteIDModule/BLE_TX.h b/RemoteIDModule/BLE_TX.h index f3dc55a..0d73e09 100644 --- a/RemoteIDModule/BLE_TX.h +++ b/RemoteIDModule/BLE_TX.h @@ -13,6 +13,7 @@ class BLE_TX : public Transmitter { bool transmit_legacy(ODID_UAS_Data &UAS_data); private: + bool initialised; uint8_t msg_counters[ODID_MSG_COUNTER_AMOUNT]; uint8_t legacy_payload[36]; uint8_t longrange_payload[250]; diff --git a/RemoteIDModule/DroneCAN.cpp b/RemoteIDModule/DroneCAN.cpp index 443cb4e..c21aed9 100644 --- a/RemoteIDModule/DroneCAN.cpp +++ b/RemoteIDModule/DroneCAN.cpp @@ -7,11 +7,14 @@ #include "version.h" #include #include "DroneCAN.h" +#include "parameters.h" + #include #include #include #include #include +#include #include #include #include @@ -19,11 +22,13 @@ #include #include -#define BOARD_ID 10001 +#ifndef CAN_BOARD_ID +#define CAN_BOARD_ID 10001 +#endif + #ifndef CAN_APP_NODE_NAME #define CAN_APP_NODE_NAME "ArduPilot RemoteIDModule" #endif -#define CAN_DEFAULT_NODE_ID 0 // use DNA #define UNUSED(x) (void)(x) @@ -41,9 +46,9 @@ void DroneCAN::init(void) canardInit(&canard, (uint8_t *)canard_memory_pool, sizeof(canard_memory_pool), onTransferReceived_trampoline, shouldAcceptTransfer_trampoline, NULL); -#if CAN_DEFAULT_NODE_ID - canardSetLocalNodeID(&canard, CAN_DEFAULT_NODE_ID); -#endif + if (g.can_node > 0 && g.can_node < 128) { + canardSetLocalNodeID(&canard, g.can_node); + } canard.user_reference = (void*)this; } @@ -144,6 +149,9 @@ void DroneCAN::onTransferReceived(CanardInstance* ins, Serial.printf("Got OperatorID\n"); handle_OperatorID(transfer); break; + case UAVCAN_PROTOCOL_PARAM_GETSET_ID: + handle_param_getset(ins, transfer); + break; default: //Serial.printf("reject %u\n", transfer->data_type_id); break; @@ -171,6 +179,7 @@ bool DroneCAN::shouldAcceptTransfer(const CanardInstance* ins, ACCEPT_ID(DRONECAN_REMOTEID_SELFID); ACCEPT_ID(DRONECAN_REMOTEID_OPERATORID); ACCEPT_ID(DRONECAN_REMOTEID_SYSTEM); + ACCEPT_ID(UAVCAN_PROTOCOL_PARAM_GETSET); return true; } //Serial.printf("%u: reject ID 0x%x\n", millis(), data_type_id); @@ -334,8 +343,8 @@ void DroneCAN::handle_get_node_info(CanardInstance* ins, CanardRxTransfer* trans readUniqueID(pkt.hardware_version.unique_id); - pkt.hardware_version.major = BOARD_ID >> 8; - pkt.hardware_version.minor = BOARD_ID & 0xFF; + pkt.hardware_version.major = CAN_BOARD_ID >> 8; + pkt.hardware_version.minor = CAN_BOARD_ID & 0xFF; snprintf((char*)pkt.name.data, sizeof(pkt.name.data), "%s", CAN_APP_NODE_NAME); pkt.name.len = strnlen((char*)pkt.name.data, sizeof(pkt.name.data)); @@ -534,6 +543,142 @@ void DroneCAN::handle_Location(CanardRxTransfer* transfer) COPY_FIELD(timestamp_accuracy); } +/* + handle parameter GetSet request + */ +void DroneCAN::handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer) +{ + uavcan_protocol_param_GetSetRequest req; + if (uavcan_protocol_param_GetSetRequest_decode(transfer, &req)) { + return; + } + + uavcan_protocol_param_GetSetResponse pkt {}; + + const Parameters::Param *vp = nullptr; + + if (req.name.len != 0 && req.name.len > PARAM_NAME_MAX_LEN) { + vp = nullptr; + } else if (req.name.len != 0 && req.name.len <= PARAM_NAME_MAX_LEN) { + memcpy((char *)pkt.name.data, (char *)req.name.data, req.name.len); + vp = Parameters::find((char *)pkt.name.data); + } else { + vp = Parameters::find_by_index(req.index); + } + if (vp != nullptr && req.name.len != 0 && req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_EMPTY) { + // param set + switch (vp->ptype) { + case Parameters::ParamType::UINT8: + if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) { + return; + } + vp->set_uint8(uint8_t(req.value.integer_value)); + break; + case Parameters::ParamType::UINT32: + if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE) { + return; + } + vp->set_uint32(uint32_t(req.value.integer_value)); + break; + case Parameters::ParamType::FLOAT: + if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE) { + return; + } + vp->set_float(req.value.real_value); + break; + case Parameters::ParamType::CHAR20: { + if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) { + return; + } + char v[21] {}; + strncpy(v, (const char *)&req.value.string_value.data[0], req.value.string_value.len); + vp->set_char20(v); + break; + } + case Parameters::ParamType::CHAR64: { + if (req.value.union_tag != UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE) { + return; + } + char v[65] {}; + strncpy(v, (const char *)&req.value.string_value.data[0], req.value.string_value.len); + vp->set_char64(v); + break; + } + default: + return; + } + } + if (vp != nullptr) { + switch (vp->ptype) { + case Parameters::ParamType::UINT8: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.value.integer_value = vp->get_uint8(); + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.default_value.integer_value = uint8_t(vp->default_value); + pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.min_value.integer_value = uint8_t(vp->min_value); + pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.max_value.integer_value = uint8_t(vp->max_value); + break; + case Parameters::ParamType::UINT32: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.value.integer_value = vp->get_uint32(); + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_INTEGER_VALUE; + pkt.default_value.integer_value = uint32_t(vp->default_value); + pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.min_value.integer_value = uint32_t(vp->min_value); + pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_INTEGER_VALUE; + pkt.max_value.integer_value = uint32_t(vp->max_value); + break; + case Parameters::ParamType::FLOAT: + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; + pkt.value.real_value = vp->get_float(); + pkt.default_value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_REAL_VALUE; + pkt.default_value.real_value = vp->default_value; + pkt.min_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE; + pkt.min_value.real_value = vp->min_value; + pkt.max_value.union_tag = UAVCAN_PROTOCOL_PARAM_NUMERICVALUE_REAL_VALUE; + pkt.max_value.real_value = vp->max_value; + break; + case Parameters::ParamType::CHAR20: { + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE; + const char *s = vp->get_char20(); + if (vp->flags & PARAM_FLAG_HIDDEN) { + s = "********"; + } + strncpy((char*)pkt.value.string_value.data, s, sizeof(pkt.value.string_value.data)); + pkt.value.string_value.len = strlen(s); + break; + } + case Parameters::ParamType::CHAR64: { + pkt.value.union_tag = UAVCAN_PROTOCOL_PARAM_VALUE_STRING_VALUE; + const char *s = vp->get_char64(); + strncpy((char*)pkt.value.string_value.data, s, sizeof(pkt.value.string_value.data)); + pkt.value.string_value.len = strlen(s); + break; + } + default: + return; + } + pkt.name.len = strlen(vp->name); + strncpy((char *)pkt.name.data, vp->name, sizeof(pkt.name.data)); + } + + uint8_t buffer[UAVCAN_PROTOCOL_PARAM_GETSET_RESPONSE_MAX_SIZE] {}; + uint16_t total_size = uavcan_protocol_param_GetSetResponse_encode(&pkt, buffer); + + canardRequestOrRespond(ins, + transfer->source_node_id, + UAVCAN_PROTOCOL_PARAM_GETSET_SIGNATURE, + UAVCAN_PROTOCOL_PARAM_GETSET_ID, + &transfer->transfer_id, + transfer->priority, + CanardResponse, + &buffer[0], + total_size); +} + + #if 0 // xprintf is useful when debugging in C code such as libcanard extern "C" { diff --git a/RemoteIDModule/DroneCAN.h b/RemoteIDModule/DroneCAN.h index 43acf3e..9086ff4 100644 --- a/RemoteIDModule/DroneCAN.h +++ b/RemoteIDModule/DroneCAN.h @@ -55,6 +55,7 @@ class DroneCAN : public Transport { void handle_OperatorID(CanardRxTransfer* transfer); void handle_System(CanardRxTransfer* transfer); void handle_Location(CanardRxTransfer* transfer); + void handle_param_getset(CanardInstance* ins, CanardRxTransfer* transfer); public: void onTransferReceived(CanardInstance* ins, CanardRxTransfer* transfer); diff --git a/RemoteIDModule/Makefile b/RemoteIDModule/Makefile index 9954ea8..f3a199e 100644 --- a/RemoteIDModule/Makefile +++ b/RemoteIDModule/Makefile @@ -38,11 +38,15 @@ headers: @../scripts/git-version.sh @cd .. && scripts/regen_headers.sh -ArduRemoteID-%.bin: *.cpp *.ino *.h +romfs_files.h: web/*.html web/js/*.js web/styles/*css web/images/*.jpg + @../scripts/make_romfs.py romfs_files.h web/*.html web/js/*.js web/styles/*css web/images/*.jpg + +ArduRemoteID-%.bin: *.cpp *.ino *.h romfs_files.h @echo "Building $* on $(CHIP)" @BUILD_FLAGS="-DBOARD_$*" @rm -rf build build-$* - @$(ARDUINO_CLI) compile -b esp32:esp32:$(CHIP) --export-binaries --build-property build.extra_flags=-DBOARD_$* --build-property upload.maximum_size=$(APP_PARTITION_SIZE) . + @$(ARDUINO_CLI) compile -b esp32:esp32:$(CHIP) --export-binaries --build-property build.extra_flags=-DBOARD_$* --build-property upload.maximum_size=$(APP_PARTITION_SIZE) + @cp build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bin ArduRemoteID_$*_OTA.bin @echo "Merging $*" @python3 $(ESPTOOL) --chip $(CHIP) merge_bin -o ArduRemoteID-$*.bin --flash_size 4MB 0x0 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bootloader.bin 0x8000 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.partitions.bin 0xe000 $(ESP32_TOOLS)/partitions/boot_app0.bin 0x10000 build/esp32.esp32.$(CHIP)/RemoteIDModule.ino.bin @mv build build-$* @@ -58,6 +62,10 @@ upload-%: checkdev @echo "Flashing ArduRemoteID-$*.bin" $(ESPTOOL) --port $(SERDEV) write_flash 0x0 ArduRemoteID-$*.bin +uploadota-%: checkdev + @echo "Flashing ArduRemoteID-$*_OTA.bin" + $(ESPTOOL) --port $(SERDEV) write_flash 0x10000 ArduRemoteID_$*_OTA.bin + upload: upload-ESP32S3_DEV clean: diff --git a/RemoteIDModule/RemoteIDModule.ino b/RemoteIDModule/RemoteIDModule.ino index ffeccdc..2d15b35 100644 --- a/RemoteIDModule/RemoteIDModule.ino +++ b/RemoteIDModule/RemoteIDModule.ino @@ -16,6 +16,10 @@ #include "DroneCAN.h" #include "WiFi_TX.h" #include "BLE_TX.h" +#include "parameters.h" +#include "webinterface.h" +#include "check_firmware.h" +#include #if AP_DRONECAN_ENABLED static DroneCAN dronecan; @@ -26,31 +30,34 @@ static MAVLinkSerial mavlink1{Serial1, MAVLINK_COMM_0}; static MAVLinkSerial mavlink2{Serial, MAVLINK_COMM_1}; #endif -#if AP_WIFI_NAN_ENABLED static WiFi_NAN wifi; -#endif - -#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED static BLE_TX ble; -#endif #define DEBUG_BAUDRATE 57600 -#define MAVLINK_BAUDRATE 57600 // OpenDroneID output data structure static ODID_UAS_Data UAS_data; static uint32_t last_location_ms; +static WebInterface webif; + +#include "soc/soc.h" +#include "soc/rtc_cntl_reg.h" /* setup serial ports */ void setup() { + // disable brownout checking + WRITE_PERI_REG(RTC_CNTL_BROWN_OUT_REG, 0); + + g.init(); + // Serial for debug printf - Serial.begin(DEBUG_BAUDRATE); + Serial.begin(g.baudrate); // Serial1 for MAVLink - Serial1.begin(MAVLINK_BAUDRATE, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX); + Serial1.begin(g.baudrate, SERIAL_8N1, PIN_UART_RX, PIN_UART_TX); // set all fields to invalid/initial values odid_initUasData(&UAS_data); @@ -62,12 +69,8 @@ void setup() #if AP_DRONECAN_ENABLED dronecan.init(); #endif -#if AP_WIFI_NAN_ENABLED - wifi.init(); -#endif -#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED - ble.init(); -#endif + + CheckFirmware::check_OTA_running(); #if defined(PIN_CAN_EN) // optional CAN enable pin @@ -86,6 +89,10 @@ void setup() pinMode(PIN_CAN_TERM, OUTPUT); digitalWrite(PIN_CAN_TERM, HIGH); #endif + + esp_log_level_set("*", ESP_LOG_DEBUG); + + esp_ota_mark_app_valid_cancel_rollback(); } #define IMIN(x,y) ((x)<(y)?(x):(y)) @@ -219,8 +226,6 @@ static uint8_t loop_counter = 0; void loop() { - static uint32_t last_update; - #if AP_MAVLINK_ENABLED mavlink1.update(); mavlink2.update(); @@ -231,15 +236,9 @@ void loop() const uint32_t now_ms = millis(); - // we call BT4 send at 5x the desired rate as it has to split the pkts 5 ways - const uint32_t rate_divider = 5; - - if (now_ms - last_update < 1000UL/(OUTPUT_RATE_HZ*rate_divider)) { - // not ready for a new frame yet - return; + if (g.webserver_enable) { + webif.update(); } - loop_counter++; - loop_counter %= rate_divider; // the transports have common static data, so we can just use the // first for status @@ -255,19 +254,20 @@ void loop() const uint32_t last_location_ms = transport.get_last_location_ms(); const uint32_t last_system_ms = transport.get_last_system_ms(); -#if AP_BROADCAST_ON_POWER_UP - // if we are broadcasting on powerup we always mark location valid - // so the location with default data is sent - if (!UAS_data.LocationValid) { - UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; - UAS_data.LocationValid = 1; - } -#else - // only broadcast if we have received a location at least once - if (last_location_ms == 0) { - return; + if (g.bcast_powerup) { + // if we are broadcasting on powerup we always mark location valid + // so the location with default data is sent + if (!UAS_data.LocationValid) { + UAS_data.Location.Status = ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE; + UAS_data.LocationValid = 1; + } + } else { + // only broadcast if we have received a location at least once + if (last_location_ms == 0) { + delay(1); + return; + } } -#endif if (last_location_ms == 0 || now_ms - last_location_ms > 5000) { @@ -284,24 +284,29 @@ void loop() } set_data(transport); - last_update = now_ms; -#if AP_WIFI_NAN_ENABLED - if (loop_counter == 0) { //only run on the original update rate + + static uint32_t last_update_wifi_ms; + if (g.wifi_nan_rate > 0 && + now_ms - last_update_wifi_ms > 1000/g.wifi_nan_rate) { + last_update_wifi_ms = now_ms; wifi.transmit(UAS_data); } -#endif -#if AP_BLE_LONGRANGE_ENABLED - if (loop_counter == 0) { //only run on the original update rate + static uint32_t last_update_bt5_ms; + if (g.bt5_rate > 0 && + now_ms - last_update_bt5_ms > 1000/g.bt5_rate) { + last_update_bt5_ms = now_ms; ble.transmit_longrange(UAS_data); } -#endif -#if AP_BLE_LEGACY_ENABLED - ble.transmit_legacy(UAS_data); -#endif + static uint32_t last_update_bt4_ms; + if (g.bt4_rate > 0 && + now_ms - last_update_bt4_ms > 200/g.bt4_rate) { + last_update_bt4_ms = now_ms; + ble.transmit_legacy(UAS_data); + ble.transmit_legacy_name(UAS_data); + } -#if AP_BLE_LEGACY_ENABLED || AP_BLE_LONGRANGE_ENABLED - ble.transmit_legacy_name(UAS_data); -#endif + // sleep for a bit for power saving + delay(1); } diff --git a/RemoteIDModule/WiFi_TX.cpp b/RemoteIDModule/WiFi_TX.cpp index 6f0270a..ae4ccd8 100644 --- a/RemoteIDModule/WiFi_TX.cpp +++ b/RemoteIDModule/WiFi_TX.cpp @@ -45,6 +45,10 @@ bool WiFi_NAN::init(void) bool WiFi_NAN::transmit(ODID_UAS_Data &UAS_data) { + if (!initialised) { + initialised = true; + init(); + } uint8_t buffer[1024] {}; int length; diff --git a/RemoteIDModule/WiFi_TX.h b/RemoteIDModule/WiFi_TX.h index 0e2807f..02d1568 100644 --- a/RemoteIDModule/WiFi_TX.h +++ b/RemoteIDModule/WiFi_TX.h @@ -11,6 +11,7 @@ class WiFi_NAN : public Transmitter { bool transmit(ODID_UAS_Data &UAS_data); private: + bool initialised; char ssid[32]; uint8_t WiFi_mac_addr[6]; uint8_t wifi_channel = 6; diff --git a/RemoteIDModule/board_config.h b/RemoteIDModule/board_config.h index 8fdd14b..58c2d25 100644 --- a/RemoteIDModule/board_config.h +++ b/RemoteIDModule/board_config.h @@ -5,6 +5,7 @@ #pragma once #ifdef BOARD_ESP32S3_DEV +#define BOARD_ID 1 #define PIN_CAN_TX GPIO_NUM_47 #define PIN_CAN_RX GPIO_NUM_38 @@ -12,6 +13,7 @@ #define PIN_UART_RX 17 #elif defined(BOARD_ESP32C3_DEV) +#define BOARD_ID 2 #define PIN_CAN_TX GPIO_NUM_5 #define PIN_CAN_RX GPIO_NUM_4 @@ -19,6 +21,7 @@ #define PIN_UART_RX 2 #elif defined(BOARD_BLUEMARK_DB200) +#define BOARD_ID 3 #define PIN_CAN_TX GPIO_NUM_0 // this goes to the TX pin (= input) of the NXP CAN transceiver #define PIN_CAN_RX GPIO_NUM_5 @@ -37,6 +40,7 @@ #define STATUS_LED_ON 1 #elif defined(BOARD_BLUEMARK_DB110) +#define BOARD_ID 4 #define PIN_UART_TX 5 #define PIN_UART_RX 4 diff --git a/RemoteIDModule/check_firmware.cpp b/RemoteIDModule/check_firmware.cpp new file mode 100644 index 0000000..bb4adf4 --- /dev/null +++ b/RemoteIDModule/check_firmware.cpp @@ -0,0 +1,146 @@ +#include +#include "check_firmware.h" +#include "monocypher.h" +#include "parameters.h" +#include + +/* + simple base64 decoder, not particularly efficient, but small + */ +static int32_t base64_decode(const char *s, uint8_t *out, const uint32_t max_len) +{ + static const char b64[] = "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/"; + + const char *p; + uint32_t n = 0; + uint32_t i = 0; + while (*s && (p=strchr(b64,*s))) { + const uint8_t idx = (p - b64); + const uint32_t byte_offset = (i*6)/8; + const uint32_t bit_offset = (i*6)%8; + out[byte_offset] &= ~((1<<(8-bit_offset))-1); + if (bit_offset < 3) { + if (byte_offset >= max_len) { + break; + } + out[byte_offset] |= (idx << (2-bit_offset)); + n = byte_offset+1; + } else { + if (byte_offset >= max_len) { + break; + } + out[byte_offset] |= (idx >> (bit_offset-2)); + n = byte_offset+1; + if (byte_offset+1 >= max_len) { + break; + } + out[byte_offset+1] = (idx << (8-(bit_offset-2))) & 0xFF; + n = byte_offset+2; + } + s++; i++; + } + + if ((n > 0) && (*s == '=')) { + n -= 1; + } + + return n; +} + + +bool CheckFirmware::check_partition(const uint8_t *flash, uint32_t flash_len, + const uint8_t *lead_bytes, uint32_t lead_length, + const app_descriptor_t *ad, const uint8_t public_key[32]) +{ + crypto_check_ctx ctx {}; + crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; + crypto_check_init(actx, ad->sign_signature, public_key); + if (lead_length > 0) { + crypto_check_update(actx, lead_bytes, lead_length); + } + crypto_check_update(actx, &flash[lead_length], flash_len-lead_length); + return crypto_check_final(actx) == 0; +} + +bool CheckFirmware::check_OTA_partition(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length) +{ + Serial.printf("Checking partition %s\n", part->label); + spi_flash_mmap_handle_t handle; + const void *ptr = nullptr; + auto ret = esp_partition_mmap(part, 0, part->size, SPI_FLASH_MMAP_DATA, &ptr, &handle); + if (ret != ESP_OK) { + Serial.printf("mmap failed\n"); + return false; + } + const uint8_t sig_rev[] = APP_DESCRIPTOR_REV; + uint8_t sig[8]; + for (uint8_t i=0; i<8; i++) { + sig[i] = sig_rev[7-i]; + } + const app_descriptor_t *ad = (app_descriptor_t *)memmem(ptr, part->size, sig, sizeof(sig)); + if (ad == nullptr) { + Serial.printf("app_descriptor not found\n"); + spi_flash_munmap(handle); + return false; + } + Serial.printf("app descriptor at 0x%x size=%u id=%u\n", unsigned(ad)-unsigned(ptr), ad->image_size, ad->board_id); + const uint32_t img_len = uint32_t(uintptr_t(ad) - uintptr_t(ptr)); + if (ad->image_size != img_len) { + Serial.printf("app_descriptor bad size %u\n", ad->image_size); + spi_flash_munmap(handle); + return false; + } + + for (uint8_t i=0; i +#include + +// reversed app descriptor. Reversed used to prevent it appearing in flash +#define APP_DESCRIPTOR_REV { 0x19, 0x75, 0xe2, 0x46, 0x37, 0xf1, 0x2a, 0x43 } + +class CheckFirmware { +public: + typedef struct { + uint8_t sig[8]; + uint32_t board_id; + uint32_t image_size; + uint8_t sign_signature[64]; + } app_descriptor_t; + + // check the firmware on the partition which will be updated by OTA + static bool check_OTA_next(const uint8_t *lead_bytes, uint32_t lead_length); + static bool check_OTA_running(void); + +private: + static bool check_OTA_partition(const esp_partition_t *part, const uint8_t *lead_bytes, uint32_t lead_length); + static bool check_partition(const uint8_t *flash, uint32_t flash_len, + const uint8_t *lead_bytes, uint32_t lead_length, + const app_descriptor_t *ad, const uint8_t public_key[32]); +}; + diff --git a/RemoteIDModule/monocypher.cpp b/RemoteIDModule/monocypher.cpp new file mode 100644 index 0000000..32cda54 --- /dev/null +++ b/RemoteIDModule/monocypher.cpp @@ -0,0 +1,3044 @@ +// Monocypher version 3.1.2 +// +// This file is dual-licensed. Choose whichever licence you want from +// the two licences listed below. +// +// The first licence is a regular 2-clause BSD licence. The second licence +// is the CC-0 from Creative Commons. It is intended to release Monocypher +// to the public domain. The BSD licence serves as a fallback option. +// +// SPDX-License-Identifier: BSD-2-Clause OR CC0-1.0 +// +// ------------------------------------------------------------------------ +// +// Copyright (c) 2017-2020, Loup Vaillant +// All rights reserved. +// +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the +// distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ------------------------------------------------------------------------ +// +// Written in 2017-2020 by Loup Vaillant +// +// To the extent possible under law, the author(s) have dedicated all copyright +// and related neighboring rights to this software to the public domain +// worldwide. This software is distributed without any warranty. +// +// You should have received a copy of the CC0 Public Domain Dedication along +// with this software. If not, see +// + +#include "monocypher.h" + +// we don't need Argon2 +#define MONOCYPHER_ARGON2_ENABLE 0 + +// we want the bootloader to be as small as possible +#define BLAKE2_NO_UNROLLING 1 + +///////////////// +/// Utilities /// +///////////////// +#define FOR_T(type, i0, start, end) for (type i0 = (start); i0 < (end); i0++) +#define FOR(i1, start, end) FOR_T(size_t, i1, start, end) +#define COPY(dst, src, size) FOR(i2, 0, size) (dst)[i2] = (src)[i2] +#define ZERO(buf, size) FOR(i3, 0, size) (buf)[i3] = 0 +#define WIPE_CTX(ctx) crypto_wipe(ctx , sizeof(*(ctx))) +#define WIPE_BUFFER(buffer) crypto_wipe(buffer, sizeof(buffer)) +#define MIN(a, b) ((a) <= (b) ? (a) : (b)) +#define MAX(a, b) ((a) >= (b) ? (a) : (b)) + +typedef int8_t i8; +typedef uint8_t u8; +typedef int16_t i16; +typedef uint32_t u32; +typedef int32_t i32; +typedef int64_t i64; +typedef uint64_t u64; + +static const u8 zero[128] = {0}; + +// returns the smallest positive integer y such that +// (x + y) % pow_2 == 0 +// Basically, it's how many bytes we need to add to "align" x. +// Only works when pow_2 is a power of 2. +// Note: we use ~x+1 instead of -x to avoid compiler warnings +static size_t align(size_t x, size_t pow_2) +{ + return (~x + 1) & (pow_2 - 1); +} + +static u32 load24_le(const u8 s[3]) +{ + return (u32)s[0] + | ((u32)s[1] << 8) + | ((u32)s[2] << 16); +} + +static u32 load32_le(const u8 s[4]) +{ + return (u32)s[0] + | ((u32)s[1] << 8) + | ((u32)s[2] << 16) + | ((u32)s[3] << 24); +} + +static u64 load64_le(const u8 s[8]) +{ + return load32_le(s) | ((u64)load32_le(s+4) << 32); +} + +static void store32_le(u8 out[4], u32 in) +{ + out[0] = in & 0xff; + out[1] = (in >> 8) & 0xff; + out[2] = (in >> 16) & 0xff; + out[3] = (in >> 24) & 0xff; +} + +static void store64_le(u8 out[8], u64 in) +{ + store32_le(out , (u32)in ); + store32_le(out + 4, in >> 32); +} + +static void load32_le_buf (u32 *dst, const u8 *src, size_t size) { + FOR(i, 0, size) { dst[i] = load32_le(src + i*4); } +} +static void load64_le_buf (u64 *dst, const u8 *src, size_t size) { + FOR(i, 0, size) { dst[i] = load64_le(src + i*8); } +} +static void store32_le_buf(u8 *dst, const u32 *src, size_t size) { + FOR(i, 0, size) { store32_le(dst + i*4, src[i]); } +} +static void store64_le_buf(u8 *dst, const u64 *src, size_t size) { + FOR(i, 0, size) { store64_le(dst + i*8, src[i]); } +} + +static u64 rotr64(u64 x, u64 n) { return (x >> n) ^ (x << (64 - n)); } +static u32 rotl32(u32 x, u32 n) { return (x << n) ^ (x >> (32 - n)); } + +static int neq0(u64 diff) +{ // constant time comparison to zero + // return diff != 0 ? -1 : 0 + u64 half = (diff >> 32) | ((u32)diff); + return (1 & ((half - 1) >> 32)) - 1; +} + +static u64 x16(const u8 a[16], const u8 b[16]) +{ + return (load64_le(a + 0) ^ load64_le(b + 0)) + | (load64_le(a + 8) ^ load64_le(b + 8)); +} +static u64 x32(const u8 a[32],const u8 b[32]){return x16(a,b)| x16(a+16, b+16);} +static u64 x64(const u8 a[64],const u8 b[64]){return x32(a,b)| x32(a+32, b+32);} +int crypto_verify16(const u8 a[16], const u8 b[16]){ return neq0(x16(a, b)); } +int crypto_verify32(const u8 a[32], const u8 b[32]){ return neq0(x32(a, b)); } +int crypto_verify64(const u8 a[64], const u8 b[64]){ return neq0(x64(a, b)); } + +void crypto_wipe(void *secret, size_t size) +{ + volatile u8 *v_secret = (u8*)secret; + ZERO(v_secret, size); +} + +///////////////// +/// Chacha 20 /// +///////////////// +#define QUARTERROUND(a, b, c, d) \ + a += b; d = rotl32(d ^ a, 16); \ + c += d; b = rotl32(b ^ c, 12); \ + a += b; d = rotl32(d ^ a, 8); \ + c += d; b = rotl32(b ^ c, 7) + +static void chacha20_rounds(u32 out[16], const u32 in[16]) +{ + // The temporary variables make Chacha20 10% faster. + u32 t0 = in[ 0]; u32 t1 = in[ 1]; u32 t2 = in[ 2]; u32 t3 = in[ 3]; + u32 t4 = in[ 4]; u32 t5 = in[ 5]; u32 t6 = in[ 6]; u32 t7 = in[ 7]; + u32 t8 = in[ 8]; u32 t9 = in[ 9]; u32 t10 = in[10]; u32 t11 = in[11]; + u32 t12 = in[12]; u32 t13 = in[13]; u32 t14 = in[14]; u32 t15 = in[15]; + + FOR (i, 0, 10) { // 20 rounds, 2 rounds per loop. + QUARTERROUND(t0, t4, t8 , t12); // column 0 + QUARTERROUND(t1, t5, t9 , t13); // column 1 + QUARTERROUND(t2, t6, t10, t14); // column 2 + QUARTERROUND(t3, t7, t11, t15); // column 3 + QUARTERROUND(t0, t5, t10, t15); // diagonal 0 + QUARTERROUND(t1, t6, t11, t12); // diagonal 1 + QUARTERROUND(t2, t7, t8 , t13); // diagonal 2 + QUARTERROUND(t3, t4, t9 , t14); // diagonal 3 + } + out[ 0] = t0; out[ 1] = t1; out[ 2] = t2; out[ 3] = t3; + out[ 4] = t4; out[ 5] = t5; out[ 6] = t6; out[ 7] = t7; + out[ 8] = t8; out[ 9] = t9; out[10] = t10; out[11] = t11; + out[12] = t12; out[13] = t13; out[14] = t14; out[15] = t15; +} + +static void chacha20_init_key(u32 block[16], const u8 key[32]) +{ + load32_le_buf(block , (const u8*)"expand 32-byte k", 4); // constant + load32_le_buf(block+4, key , 8); // key +} + +void crypto_hchacha20(u8 out[32], const u8 key[32], const u8 in [16]) +{ + u32 block[16]; + chacha20_init_key(block, key); + // input + load32_le_buf(block + 12, in, 4); + chacha20_rounds(block, block); + // prevent reversal of the rounds by revealing only half of the buffer. + store32_le_buf(out , block , 4); // constant + store32_le_buf(out+16, block+12, 4); // counter and nonce + WIPE_BUFFER(block); +} + +u64 crypto_chacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, const u8 key[32], const u8 nonce[8], + u64 ctr) +{ + u32 input[16]; + chacha20_init_key(input, key); + input[12] = (u32) ctr; + input[13] = (u32)(ctr >> 32); + load32_le_buf(input+14, nonce, 2); + + // Whole blocks + u32 pool[16]; + size_t nb_blocks = text_size >> 6; + FOR (i, 0, nb_blocks) { + chacha20_rounds(pool, input); + if (plain_text != 0) { + FOR (j, 0, 16) { + u32 p = pool[j] + input[j]; + store32_le(cipher_text, p ^ load32_le(plain_text)); + cipher_text += 4; + plain_text += 4; + } + } else { + FOR (j, 0, 16) { + u32 p = pool[j] + input[j]; + store32_le(cipher_text, p); + cipher_text += 4; + } + } + input[12]++; + if (input[12] == 0) { + input[13]++; + } + } + text_size &= 63; + + // Last (incomplete) block + if (text_size > 0) { + if (plain_text == 0) { + plain_text = zero; + } + chacha20_rounds(pool, input); + u8 tmp[64]; + FOR (i, 0, 16) { + store32_le(tmp + i*4, pool[i] + input[i]); + } + FOR (i, 0, text_size) { + cipher_text[i] = tmp[i] ^ plain_text[i]; + } + WIPE_BUFFER(tmp); + } + ctr = input[12] + ((u64)input[13] << 32) + (text_size > 0); + + WIPE_BUFFER(pool); + WIPE_BUFFER(input); + return ctr; +} + +u32 crypto_ietf_chacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[12], u32 ctr) +{ + u64 big_ctr = ctr + ((u64)load32_le(nonce) << 32); + return (u32)crypto_chacha20_ctr(cipher_text, plain_text, text_size, + key, nonce + 4, big_ctr); +} + +u64 crypto_xchacha20_ctr(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[24], u64 ctr) +{ + u8 sub_key[32]; + crypto_hchacha20(sub_key, key, nonce); + ctr = crypto_chacha20_ctr(cipher_text, plain_text, text_size, + sub_key, nonce+16, ctr); + WIPE_BUFFER(sub_key); + return ctr; +} + +void crypto_chacha20(u8 *cipher_text, const u8 *plain_text, size_t text_size, + const u8 key[32], const u8 nonce[8]) +{ + crypto_chacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); + +} +void crypto_ietf_chacha20(u8 *cipher_text, const u8 *plain_text, + size_t text_size, + const u8 key[32], const u8 nonce[12]) +{ + crypto_ietf_chacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); +} + +void crypto_xchacha20(u8 *cipher_text, const u8 *plain_text, size_t text_size, + const u8 key[32], const u8 nonce[24]) +{ + crypto_xchacha20_ctr(cipher_text, plain_text, text_size, key, nonce, 0); +} + +///////////////// +/// Poly 1305 /// +///////////////// + +// h = (h + c) * r +// preconditions: +// ctx->h <= 4_ffffffff_ffffffff_ffffffff_ffffffff +// ctx->c <= 1_ffffffff_ffffffff_ffffffff_ffffffff +// ctx->r <= 0ffffffc_0ffffffc_0ffffffc_0fffffff +// Postcondition: +// ctx->h <= 4_ffffffff_ffffffff_ffffffff_ffffffff +static void poly_block(crypto_poly1305_ctx *ctx) +{ + // s = h + c, without carry propagation + const u64 s0 = ctx->h[0] + (u64)ctx->c[0]; // s0 <= 1_fffffffe + const u64 s1 = ctx->h[1] + (u64)ctx->c[1]; // s1 <= 1_fffffffe + const u64 s2 = ctx->h[2] + (u64)ctx->c[2]; // s2 <= 1_fffffffe + const u64 s3 = ctx->h[3] + (u64)ctx->c[3]; // s3 <= 1_fffffffe + const u32 s4 = ctx->h[4] + ctx->c[4]; // s4 <= 5 + + // Local all the things! + const u32 r0 = ctx->r[0]; // r0 <= 0fffffff + const u32 r1 = ctx->r[1]; // r1 <= 0ffffffc + const u32 r2 = ctx->r[2]; // r2 <= 0ffffffc + const u32 r3 = ctx->r[3]; // r3 <= 0ffffffc + const u32 rr0 = (r0 >> 2) * 5; // rr0 <= 13fffffb // lose 2 bits... + const u32 rr1 = (r1 >> 2) + r1; // rr1 <= 13fffffb // rr1 == (r1 >> 2) * 5 + const u32 rr2 = (r2 >> 2) + r2; // rr2 <= 13fffffb // rr1 == (r2 >> 2) * 5 + const u32 rr3 = (r3 >> 2) + r3; // rr3 <= 13fffffb // rr1 == (r3 >> 2) * 5 + + // (h + c) * r, without carry propagation + const u64 x0 = s0*r0+ s1*rr3+ s2*rr2+ s3*rr1+ s4*rr0; // <= 97ffffe007fffff8 + const u64 x1 = s0*r1+ s1*r0 + s2*rr3+ s3*rr2+ s4*rr1; // <= 8fffffe20ffffff6 + const u64 x2 = s0*r2+ s1*r1 + s2*r0 + s3*rr3+ s4*rr2; // <= 87ffffe417fffff4 + const u64 x3 = s0*r3+ s1*r2 + s2*r1 + s3*r0 + s4*rr3; // <= 7fffffe61ffffff2 + const u32 x4 = s4 * (r0 & 3); // ...recover 2 bits // <= f + + // partial reduction modulo 2^130 - 5 + const u32 u5 = x4 + (x3 >> 32); // u5 <= 7ffffff5 + const u64 u0 = (u5 >> 2) * 5 + (x0 & 0xffffffff); + const u64 u1 = (u0 >> 32) + (x1 & 0xffffffff) + (x0 >> 32); + const u64 u2 = (u1 >> 32) + (x2 & 0xffffffff) + (x1 >> 32); + const u64 u3 = (u2 >> 32) + (x3 & 0xffffffff) + (x2 >> 32); + const u64 u4 = (u3 >> 32) + (u5 & 3); + + // Update the hash + ctx->h[0] = (u32)u0; // u0 <= 1_9ffffff0 + ctx->h[1] = (u32)u1; // u1 <= 1_97ffffe0 + ctx->h[2] = (u32)u2; // u2 <= 1_8fffffe2 + ctx->h[3] = (u32)u3; // u3 <= 1_87ffffe4 + ctx->h[4] = (u32)u4; // u4 <= 4 +} + +// (re-)initialises the input counter and input buffer +static void poly_clear_c(crypto_poly1305_ctx *ctx) +{ + ZERO(ctx->c, 4); + ctx->c_idx = 0; +} + +static void poly_take_input(crypto_poly1305_ctx *ctx, u8 input) +{ + size_t word = ctx->c_idx >> 2; + size_t byte = ctx->c_idx & 3; + ctx->c[word] |= (u32)input << (byte * 8); + ctx->c_idx++; +} + +static void poly_update(crypto_poly1305_ctx *ctx, + const u8 *message, size_t message_size) +{ + FOR (i, 0, message_size) { + poly_take_input(ctx, message[i]); + if (ctx->c_idx == 16) { + poly_block(ctx); + poly_clear_c(ctx); + } + } +} + +void crypto_poly1305_init(crypto_poly1305_ctx *ctx, const u8 key[32]) +{ + // Initial hash is zero + ZERO(ctx->h, 5); + // add 2^130 to every input block + ctx->c[4] = 1; + poly_clear_c(ctx); + // load r and pad (r has some of its bits cleared) + load32_le_buf(ctx->r , key , 4); + load32_le_buf(ctx->pad, key+16, 4); + FOR (i, 0, 1) { ctx->r[i] &= 0x0fffffff; } + FOR (i, 1, 4) { ctx->r[i] &= 0x0ffffffc; } +} + +void crypto_poly1305_update(crypto_poly1305_ctx *ctx, + const u8 *message, size_t message_size) +{ + if (message_size == 0) { + return; + } + // Align ourselves with block boundaries + size_t aligned = MIN(align(ctx->c_idx, 16), message_size); + poly_update(ctx, message, aligned); + message += aligned; + message_size -= aligned; + + // Process the message block by block + size_t nb_blocks = message_size >> 4; + FOR (i, 0, nb_blocks) { + load32_le_buf(ctx->c, message, 4); + poly_block(ctx); + message += 16; + } + if (nb_blocks > 0) { + poly_clear_c(ctx); + } + message_size &= 15; + + // remaining bytes + poly_update(ctx, message, message_size); +} + +void crypto_poly1305_final(crypto_poly1305_ctx *ctx, u8 mac[16]) +{ + // Process the last block (if any) + if (ctx->c_idx != 0) { + // move the final 1 according to remaining input length + // (We may add less than 2^130 to the last input block) + ctx->c[4] = 0; + poly_take_input(ctx, 1); + // one last hash update + poly_block(ctx); + } + + // check if we should subtract 2^130-5 by performing the + // corresponding carry propagation. + u64 c = 5; + FOR (i, 0, 4) { + c += ctx->h[i]; + c >>= 32; + } + c += ctx->h[4]; + c = (c >> 2) * 5; // shift the carry back to the beginning + // c now indicates how many times we should subtract 2^130-5 (0 or 1) + FOR (i, 0, 4) { + c += (u64)ctx->h[i] + ctx->pad[i]; + store32_le(mac + i*4, (u32)c); + c = c >> 32; + } + WIPE_CTX(ctx); +} + +void crypto_poly1305(u8 mac[16], const u8 *message, + size_t message_size, const u8 key[32]) +{ + crypto_poly1305_ctx ctx; + crypto_poly1305_init (&ctx, key); + crypto_poly1305_update(&ctx, message, message_size); + crypto_poly1305_final (&ctx, mac); +} + +//////////////// +/// Blake2 b /// +//////////////// +static const u64 iv[8] = { + 0x6a09e667f3bcc908, 0xbb67ae8584caa73b, + 0x3c6ef372fe94f82b, 0xa54ff53a5f1d36f1, + 0x510e527fade682d1, 0x9b05688c2b3e6c1f, + 0x1f83d9abfb41bd6b, 0x5be0cd19137e2179, +}; + +// increment the input offset +static void blake2b_incr(crypto_blake2b_ctx *ctx) +{ + u64 *x = ctx->input_offset; + size_t y = ctx->input_idx; + x[0] += y; + if (x[0] < y) { + x[1]++; + } +} + +static void blake2b_compress(crypto_blake2b_ctx *ctx, int is_last_block) +{ + static const u8 sigma[12][16] = { + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + { 14, 10, 4, 8, 9, 15, 13, 6, 1, 12, 0, 2, 11, 7, 5, 3 }, + { 11, 8, 12, 0, 5, 2, 15, 13, 10, 14, 3, 6, 7, 1, 9, 4 }, + { 7, 9, 3, 1, 13, 12, 11, 14, 2, 6, 5, 10, 4, 0, 15, 8 }, + { 9, 0, 5, 7, 2, 4, 10, 15, 14, 1, 11, 12, 6, 8, 3, 13 }, + { 2, 12, 6, 10, 0, 11, 8, 3, 4, 13, 7, 5, 15, 14, 1, 9 }, + { 12, 5, 1, 15, 14, 13, 4, 10, 0, 7, 6, 3, 9, 2, 8, 11 }, + { 13, 11, 7, 14, 12, 1, 3, 9, 5, 0, 15, 4, 8, 6, 2, 10 }, + { 6, 15, 14, 9, 11, 3, 0, 8, 12, 2, 13, 7, 1, 4, 10, 5 }, + { 10, 2, 8, 4, 7, 6, 1, 5, 15, 11, 9, 14, 3, 12, 13, 0 }, + { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 }, + { 14, 10, 4, 8, 9, 15, 13, 6, 1, 12, 0, 2, 11, 7, 5, 3 }, + }; + + // init work vector + u64 v0 = ctx->hash[0]; u64 v8 = iv[0]; + u64 v1 = ctx->hash[1]; u64 v9 = iv[1]; + u64 v2 = ctx->hash[2]; u64 v10 = iv[2]; + u64 v3 = ctx->hash[3]; u64 v11 = iv[3]; + u64 v4 = ctx->hash[4]; u64 v12 = iv[4] ^ ctx->input_offset[0]; + u64 v5 = ctx->hash[5]; u64 v13 = iv[5] ^ ctx->input_offset[1]; + u64 v6 = ctx->hash[6]; u64 v14 = iv[6] ^ (u64)~(is_last_block - 1); + u64 v7 = ctx->hash[7]; u64 v15 = iv[7]; + + // mangle work vector + u64 *input = ctx->input; +#define BLAKE2_G(a, b, c, d, x, y) \ + a += b + x; d = rotr64(d ^ a, 32); \ + c += d; b = rotr64(b ^ c, 24); \ + a += b + y; d = rotr64(d ^ a, 16); \ + c += d; b = rotr64(b ^ c, 63) +#define BLAKE2_ROUND(i) \ + BLAKE2_G(v0, v4, v8 , v12, input[sigma[i][ 0]], input[sigma[i][ 1]]); \ + BLAKE2_G(v1, v5, v9 , v13, input[sigma[i][ 2]], input[sigma[i][ 3]]); \ + BLAKE2_G(v2, v6, v10, v14, input[sigma[i][ 4]], input[sigma[i][ 5]]); \ + BLAKE2_G(v3, v7, v11, v15, input[sigma[i][ 6]], input[sigma[i][ 7]]); \ + BLAKE2_G(v0, v5, v10, v15, input[sigma[i][ 8]], input[sigma[i][ 9]]); \ + BLAKE2_G(v1, v6, v11, v12, input[sigma[i][10]], input[sigma[i][11]]); \ + BLAKE2_G(v2, v7, v8 , v13, input[sigma[i][12]], input[sigma[i][13]]); \ + BLAKE2_G(v3, v4, v9 , v14, input[sigma[i][14]], input[sigma[i][15]]) + +#ifdef BLAKE2_NO_UNROLLING + FOR (i, 0, 12) { + BLAKE2_ROUND(i); + } +#else + BLAKE2_ROUND(0); BLAKE2_ROUND(1); BLAKE2_ROUND(2); BLAKE2_ROUND(3); + BLAKE2_ROUND(4); BLAKE2_ROUND(5); BLAKE2_ROUND(6); BLAKE2_ROUND(7); + BLAKE2_ROUND(8); BLAKE2_ROUND(9); BLAKE2_ROUND(10); BLAKE2_ROUND(11); +#endif + + // update hash + ctx->hash[0] ^= v0 ^ v8; ctx->hash[1] ^= v1 ^ v9; + ctx->hash[2] ^= v2 ^ v10; ctx->hash[3] ^= v3 ^ v11; + ctx->hash[4] ^= v4 ^ v12; ctx->hash[5] ^= v5 ^ v13; + ctx->hash[6] ^= v6 ^ v14; ctx->hash[7] ^= v7 ^ v15; +} + +static void blake2b_set_input(crypto_blake2b_ctx *ctx, u8 input, size_t index) +{ + if (index == 0) { + ZERO(ctx->input, 16); + } + size_t word = index >> 3; + size_t byte = index & 7; + ctx->input[word] |= (u64)input << (byte << 3); + +} + +static void blake2b_end_block(crypto_blake2b_ctx *ctx) +{ + if (ctx->input_idx == 128) { // If buffer is full, + blake2b_incr(ctx); // update the input offset + blake2b_compress(ctx, 0); // and compress the (not last) block + ctx->input_idx = 0; + } +} + +static void blake2b_update(crypto_blake2b_ctx *ctx, + const u8 *message, size_t message_size) +{ + FOR (i, 0, message_size) { + blake2b_end_block(ctx); + blake2b_set_input(ctx, message[i], ctx->input_idx); + ctx->input_idx++; + } +} + +void crypto_blake2b_general_init(crypto_blake2b_ctx *ctx, size_t hash_size, + const u8 *key, size_t key_size) +{ + // initial hash + COPY(ctx->hash, iv, 8); + ctx->hash[0] ^= 0x01010000 ^ (key_size << 8) ^ hash_size; + + ctx->input_offset[0] = 0; // beginning of the input, no offset + ctx->input_offset[1] = 0; // beginning of the input, no offset + ctx->hash_size = hash_size; // remember the hash size we want + ctx->input_idx = 0; + + // if there is a key, the first block is that key (padded with zeroes) + if (key_size > 0) { + u8 key_block[128] = {0}; + COPY(key_block, key, key_size); + // same as calling crypto_blake2b_update(ctx, key_block , 128) + load64_le_buf(ctx->input, key_block, 16); + ctx->input_idx = 128; + } +} + +void crypto_blake2b_init(crypto_blake2b_ctx *ctx) +{ + crypto_blake2b_general_init(ctx, 64, 0, 0); +} + +void crypto_blake2b_update(crypto_blake2b_ctx *ctx, + const u8 *message, size_t message_size) +{ + if (message_size == 0) { + return; + } + // Align ourselves with block boundaries + size_t aligned = MIN(align(ctx->input_idx, 128), message_size); + blake2b_update(ctx, message, aligned); + message += aligned; + message_size -= aligned; + + // Process the message block by block + FOR (i, 0, message_size >> 7) { // number of blocks + blake2b_end_block(ctx); + load64_le_buf(ctx->input, message, 16); + message += 128; + ctx->input_idx = 128; + } + message_size &= 127; + + // remaining bytes + blake2b_update(ctx, message, message_size); +} + +void crypto_blake2b_final(crypto_blake2b_ctx *ctx, u8 *hash) +{ + // Pad the end of the block with zeroes + FOR (i, ctx->input_idx, 128) { + blake2b_set_input(ctx, 0, i); + } + blake2b_incr(ctx); // update the input offset + blake2b_compress(ctx, 1); // compress the last block + size_t nb_words = ctx->hash_size >> 3; + store64_le_buf(hash, ctx->hash, nb_words); + FOR (i, nb_words << 3, ctx->hash_size) { + hash[i] = (ctx->hash[i >> 3] >> (8 * (i & 7))) & 0xff; + } + WIPE_CTX(ctx); +} + +void crypto_blake2b_general(u8 *hash , size_t hash_size, + const u8 *key , size_t key_size, + const u8 *message, size_t message_size) +{ + crypto_blake2b_ctx ctx; + crypto_blake2b_general_init(&ctx, hash_size, key, key_size); + crypto_blake2b_update(&ctx, message, message_size); + crypto_blake2b_final(&ctx, hash); +} + +void crypto_blake2b(u8 hash[64], const u8 *message, size_t message_size) +{ + crypto_blake2b_general(hash, 64, 0, 0, message, message_size); +} + +static void blake2b_vtable_init(void *ctx) { + crypto_blake2b_init(&((crypto_sign_ctx*)ctx)->hash); +} +static void blake2b_vtable_update(void *ctx, const u8 *m, size_t s) { + crypto_blake2b_update(&((crypto_sign_ctx*)ctx)->hash, m, s); +} +static void blake2b_vtable_final(void *ctx, u8 *h) { + crypto_blake2b_final(&((crypto_sign_ctx*)ctx)->hash, h); +} +const crypto_sign_vtable crypto_blake2b_vtable = { + crypto_blake2b, + blake2b_vtable_init, + blake2b_vtable_update, + blake2b_vtable_final, + sizeof(crypto_sign_ctx), +}; + +#if MONOCYPHER_ARGON2_ENABLE +//////////////// +/// Argon2 i /// +//////////////// +// references to R, Z, Q etc. come from the spec + +// Argon2 operates on 1024 byte blocks. +typedef struct { u64 a[128]; } block; + +static void wipe_block(block *b) +{ + volatile u64* a = b->a; + ZERO(a, 128); +} + +// updates a Blake2 hash with a 32 bit word, little endian. +static void blake_update_32(crypto_blake2b_ctx *ctx, u32 input) +{ + u8 buf[4]; + store32_le(buf, input); + crypto_blake2b_update(ctx, buf, 4); + WIPE_BUFFER(buf); +} + +static void load_block(block *b, const u8 bytes[1024]) +{ + load64_le_buf(b->a, bytes, 128); +} + +static void store_block(u8 bytes[1024], const block *b) +{ + store64_le_buf(bytes, b->a, 128); +} + +static void copy_block(block *o,const block*in){FOR(i,0,128)o->a[i] = in->a[i];} +static void xor_block(block *o,const block*in){FOR(i,0,128)o->a[i]^= in->a[i];} + +// Hash with a virtually unlimited digest size. +// Doesn't extract more entropy than the base hash function. +// Mainly used for filling a whole kilobyte block with pseudo-random bytes. +// (One could use a stream cipher with a seed hash as the key, but +// this would introduce another dependency —and point of failure.) +static void extended_hash(u8 *digest, u32 digest_size, + const u8 *input , u32 input_size) +{ + crypto_blake2b_ctx ctx; + crypto_blake2b_general_init(&ctx, MIN(digest_size, 64), 0, 0); + blake_update_32 (&ctx, digest_size); + crypto_blake2b_update (&ctx, input, input_size); + crypto_blake2b_final (&ctx, digest); + + if (digest_size > 64) { + // the conversion to u64 avoids integer overflow on + // ludicrously big hash sizes. + u32 r = (u32)(((u64)digest_size + 31) >> 5) - 2; + u32 i = 1; + u32 in = 0; + u32 out = 32; + while (i < r) { + // Input and output overlap. This is intentional + crypto_blake2b(digest + out, digest + in, 64); + i += 1; + in += 32; + out += 32; + } + crypto_blake2b_general(digest + out, digest_size - (32 * r), + 0, 0, // no key + digest + in , 64); + } +} + +#define LSB(x) ((x) & 0xffffffff) +#define G(a, b, c, d) \ + a += b + 2 * LSB(a) * LSB(b); d ^= a; d = rotr64(d, 32); \ + c += d + 2 * LSB(c) * LSB(d); b ^= c; b = rotr64(b, 24); \ + a += b + 2 * LSB(a) * LSB(b); d ^= a; d = rotr64(d, 16); \ + c += d + 2 * LSB(c) * LSB(d); b ^= c; b = rotr64(b, 63) +#define ROUND(v0, v1, v2, v3, v4, v5, v6, v7, \ + v8, v9, v10, v11, v12, v13, v14, v15) \ + G(v0, v4, v8, v12); G(v1, v5, v9, v13); \ + G(v2, v6, v10, v14); G(v3, v7, v11, v15); \ + G(v0, v5, v10, v15); G(v1, v6, v11, v12); \ + G(v2, v7, v8, v13); G(v3, v4, v9, v14) + +// Core of the compression function G. Computes Z from R in place. +static void g_rounds(block *work_block) +{ + // column rounds (work_block = Q) + for (int i = 0; i < 128; i += 16) { + ROUND(work_block->a[i ], work_block->a[i + 1], + work_block->a[i + 2], work_block->a[i + 3], + work_block->a[i + 4], work_block->a[i + 5], + work_block->a[i + 6], work_block->a[i + 7], + work_block->a[i + 8], work_block->a[i + 9], + work_block->a[i + 10], work_block->a[i + 11], + work_block->a[i + 12], work_block->a[i + 13], + work_block->a[i + 14], work_block->a[i + 15]); + } + // row rounds (work_block = Z) + for (int i = 0; i < 16; i += 2) { + ROUND(work_block->a[i ], work_block->a[i + 1], + work_block->a[i + 16], work_block->a[i + 17], + work_block->a[i + 32], work_block->a[i + 33], + work_block->a[i + 48], work_block->a[i + 49], + work_block->a[i + 64], work_block->a[i + 65], + work_block->a[i + 80], work_block->a[i + 81], + work_block->a[i + 96], work_block->a[i + 97], + work_block->a[i + 112], work_block->a[i + 113]); + } +} + +// The compression function G (copy version for the first pass) +static void g_copy(block *result, const block *x, const block *y, block* tmp) +{ + copy_block(tmp , x ); // tmp = X + xor_block (tmp , y ); // tmp = X ^ Y = R + copy_block(result, tmp); // result = R (only difference with g_xor) + g_rounds (tmp); // tmp = Z + xor_block (result, tmp); // result = R ^ Z +} + +// The compression function G (xor version for subsequent passes) +static void g_xor(block *result, const block *x, const block *y, block *tmp) +{ + copy_block(tmp , x ); // tmp = X + xor_block (tmp , y ); // tmp = X ^ Y = R + xor_block (result, tmp); // result = R ^ old (only difference with g_copy) + g_rounds (tmp); // tmp = Z + xor_block (result, tmp); // result = R ^ old ^ Z +} + +// Unary version of the compression function. +// The missing argument is implied zero. +// Does the transformation in place. +static void unary_g(block *work_block, block *tmp) +{ + // work_block == R + copy_block(tmp, work_block); // tmp = R + g_rounds (work_block); // work_block = Z + xor_block (work_block, tmp); // work_block = Z ^ R +} + +// Argon2i uses a kind of stream cipher to determine which reference +// block it will take to synthesise the next block. This context hold +// that stream's state. (It's very similar to Chacha20. The block b +// is analogous to Chacha's own pool) +typedef struct { + block b; + u32 pass_number; + u32 slice_number; + u32 nb_blocks; + u32 nb_iterations; + u32 ctr; + u32 offset; +} gidx_ctx; + +// The block in the context will determine array indices. To avoid +// timing attacks, it only depends on public information. No looking +// at a previous block to seed the next. This makes offline attacks +// easier, but timing attacks are the bigger threat in many settings. +static void gidx_refresh(gidx_ctx *ctx) +{ + // seed the beginning of the block... + ctx->b.a[0] = ctx->pass_number; + ctx->b.a[1] = 0; // lane number (we have only one) + ctx->b.a[2] = ctx->slice_number; + ctx->b.a[3] = ctx->nb_blocks; + ctx->b.a[4] = ctx->nb_iterations; + ctx->b.a[5] = 1; // type: Argon2i + ctx->b.a[6] = ctx->ctr; + ZERO(ctx->b.a + 7, 121); // ...then zero the rest out + + // Shuffle the block thus: ctx->b = G((G(ctx->b, zero)), zero) + // (G "square" function), to get cheap pseudo-random numbers. + block tmp; + unary_g(&ctx->b, &tmp); + unary_g(&ctx->b, &tmp); + wipe_block(&tmp); +} + +static void gidx_init(gidx_ctx *ctx, + u32 pass_number, u32 slice_number, + u32 nb_blocks, u32 nb_iterations) +{ + ctx->pass_number = pass_number; + ctx->slice_number = slice_number; + ctx->nb_blocks = nb_blocks; + ctx->nb_iterations = nb_iterations; + ctx->ctr = 0; + + // Offset from the beginning of the segment. For the first slice + // of the first pass, we start at the *third* block, so the offset + // starts at 2, not 0. + if (pass_number != 0 || slice_number != 0) { + ctx->offset = 0; + } else { + ctx->offset = 2; + ctx->ctr++; // Compensates for missed lazy creation + gidx_refresh(ctx); // at the start of gidx_next() + } +} + +static u32 gidx_next(gidx_ctx *ctx) +{ + // lazily creates the offset block we need + if ((ctx->offset & 127) == 0) { + ctx->ctr++; + gidx_refresh(ctx); + } + u32 index = ctx->offset & 127; // save index for current call + u32 offset = ctx->offset; // save offset for current call + ctx->offset++; // update offset for next call + + // Computes the area size. + // Pass 0 : all already finished segments plus already constructed + // blocks in this segment + // Pass 1+: 3 last segments plus already constructed + // blocks in this segment. THE SPEC SUGGESTS OTHERWISE. + // I CONFORM TO THE REFERENCE IMPLEMENTATION. + int first_pass = ctx->pass_number == 0; + u32 slice_size = ctx->nb_blocks >> 2; + u32 nb_segments = first_pass ? ctx->slice_number : 3; + u32 area_size = nb_segments * slice_size + offset - 1; + + // Computes the starting position of the reference area. + // CONTRARY TO WHAT THE SPEC SUGGESTS, IT STARTS AT THE + // NEXT SEGMENT, NOT THE NEXT BLOCK. + u32 next_slice = ((ctx->slice_number + 1) & 3) * slice_size; + u32 start_pos = first_pass ? 0 : next_slice; + + // Generate offset from J1 (no need for J2, there's only one lane) + u64 j1 = ctx->b.a[index] & 0xffffffff; // pseudo-random number + u64 x = (j1 * j1) >> 32; + u64 y = (area_size * x) >> 32; + u64 z = (area_size - 1) - y; + u64 ref = start_pos + z; // ref < 2 * nb_blocks + return (u32)(ref < ctx->nb_blocks ? ref : ref - ctx->nb_blocks); +} + +// Main algorithm +void crypto_argon2i_general(u8 *hash, u32 hash_size, + void *work_area, u32 nb_blocks, + u32 nb_iterations, + const u8 *password, u32 password_size, + const u8 *salt, u32 salt_size, + const u8 *key, u32 key_size, + const u8 *ad, u32 ad_size) +{ + // work area seen as blocks (must be suitably aligned) + block *blocks = (block*)work_area; + { + crypto_blake2b_ctx ctx; + crypto_blake2b_init(&ctx); + + blake_update_32 (&ctx, 1 ); // p: number of threads + blake_update_32 (&ctx, hash_size ); + blake_update_32 (&ctx, nb_blocks ); + blake_update_32 (&ctx, nb_iterations); + blake_update_32 (&ctx, 0x13 ); // v: version number + blake_update_32 (&ctx, 1 ); // y: Argon2i + blake_update_32 (&ctx, password_size); + crypto_blake2b_update(&ctx, password, password_size); + blake_update_32 (&ctx, salt_size); + crypto_blake2b_update(&ctx, salt, salt_size); + blake_update_32 (&ctx, key_size); + crypto_blake2b_update(&ctx, key, key_size); + blake_update_32 (&ctx, ad_size); + crypto_blake2b_update(&ctx, ad, ad_size); + + u8 initial_hash[72]; // 64 bytes plus 2 words for future hashes + crypto_blake2b_final(&ctx, initial_hash); + + // fill first 2 blocks + block tmp_block; + u8 hash_area[1024]; + store32_le(initial_hash + 64, 0); // first additional word + store32_le(initial_hash + 68, 0); // second additional word + extended_hash(hash_area, 1024, initial_hash, 72); + load_block(&tmp_block, hash_area); + copy_block(blocks, &tmp_block); + + store32_le(initial_hash + 64, 1); // slight modification + extended_hash(hash_area, 1024, initial_hash, 72); + load_block(&tmp_block, hash_area); + copy_block(blocks + 1, &tmp_block); + + WIPE_BUFFER(initial_hash); + WIPE_BUFFER(hash_area); + wipe_block(&tmp_block); + } + + // Actual number of blocks + nb_blocks -= nb_blocks & 3; // round down to 4 p (p == 1 thread) + const u32 segment_size = nb_blocks >> 2; + + // fill (then re-fill) the rest of the blocks + block tmp; + gidx_ctx ctx; // public information, no need to wipe + FOR_T (u32, pass_number, 0, nb_iterations) { + int first_pass = pass_number == 0; + + FOR_T (u32, segment, 0, 4) { + gidx_init(&ctx, pass_number, segment, nb_blocks, nb_iterations); + + // On the first segment of the first pass, + // blocks 0 and 1 are already filled. + // We use the offset to skip them. + u32 start_offset = first_pass && segment == 0 ? 2 : 0; + u32 segment_start = segment * segment_size + start_offset; + u32 segment_end = (segment + 1) * segment_size; + FOR_T (u32, current_block, segment_start, segment_end) { + u32 reference_block = gidx_next(&ctx); + u32 previous_block = current_block == 0 + ? nb_blocks - 1 + : current_block - 1; + block *c = blocks + current_block; + block *p = blocks + previous_block; + block *r = blocks + reference_block; + if (first_pass) { g_copy(c, p, r, &tmp); } + else { g_xor (c, p, r, &tmp); } + } + } + } + wipe_block(&tmp); + u8 final_block[1024]; + store_block(final_block, blocks + (nb_blocks - 1)); + + // wipe work area + volatile u64 *p = (u64*)work_area; + ZERO(p, 128 * nb_blocks); + + // hash the very last block with H' into the output hash + extended_hash(hash, hash_size, final_block, 1024); + WIPE_BUFFER(final_block); +} + +void crypto_argon2i(u8 *hash, u32 hash_size, + void *work_area, u32 nb_blocks, u32 nb_iterations, + const u8 *password, u32 password_size, + const u8 *salt, u32 salt_size) +{ + crypto_argon2i_general(hash, hash_size, work_area, nb_blocks, nb_iterations, + password, password_size, salt , salt_size, 0,0,0,0); +} + +#endif // MONOCYPHER_ARGON2_ENABLE + +//////////////////////////////////// +/// Arithmetic modulo 2^255 - 19 /// +//////////////////////////////////// +// Originally taken from SUPERCOP's ref10 implementation. +// A bit bigger than TweetNaCl, over 4 times faster. + +// field element +typedef i32 fe[10]; + +// field constants +// +// fe_one : 1 +// sqrtm1 : sqrt(-1) +// d : -121665 / 121666 +// D2 : 2 * -121665 / 121666 +// lop_x, lop_y: low order point in Edwards coordinates +// ufactor : -sqrt(-1) * 2 +// A2 : 486662^2 (A squared) +static const fe fe_one = {1}; +static const fe sqrtm1 = {-32595792, -7943725, 9377950, 3500415, 12389472, + -272473, -25146209, -2005654, 326686, 11406482,}; +static const fe d = {-10913610, 13857413, -15372611, 6949391, 114729, + -8787816, -6275908, -3247719, -18696448, -12055116,}; +static const fe D2 = {-21827239, -5839606, -30745221, 13898782, 229458, + 15978800, -12551817, -6495438, 29715968, 9444199,}; +static const fe lop_x = {21352778, 5345713, 4660180, -8347857, 24143090, + 14568123, 30185756, -12247770, -33528939, 8345319,}; +static const fe lop_y = {-6952922, -1265500, 6862341, -7057498, -4037696, + -5447722, 31680899, -15325402, -19365852, 1569102,}; +static const fe ufactor = {-1917299, 15887451, -18755900, -7000830, -24778944, + 544946, -16816446, 4011309, -653372, 10741468,}; +static const fe A2 = {12721188, 3529, 0, 0, 0, 0, 0, 0, 0, 0,}; + +static void fe_0(fe h) { ZERO(h , 10); } +static void fe_1(fe h) { h[0] = 1; ZERO(h+1, 9); } + +static void fe_copy(fe h,const fe f ){FOR(i,0,10) h[i] = f[i]; } +static void fe_neg (fe h,const fe f ){FOR(i,0,10) h[i] = -f[i]; } +static void fe_add (fe h,const fe f,const fe g){FOR(i,0,10) h[i] = f[i] + g[i];} +static void fe_sub (fe h,const fe f,const fe g){FOR(i,0,10) h[i] = f[i] - g[i];} + +static void fe_cswap(fe f, fe g, int b) +{ + i32 mask = -b; // -1 = 0xffffffff + FOR (i, 0, 10) { + i32 x = (f[i] ^ g[i]) & mask; + f[i] = f[i] ^ x; + g[i] = g[i] ^ x; + } +} + +static void fe_ccopy(fe f, const fe g, int b) +{ + i32 mask = -b; // -1 = 0xffffffff + FOR (i, 0, 10) { + i32 x = (f[i] ^ g[i]) & mask; + f[i] = f[i] ^ x; + } +} + + +// Signed carry propagation +// ------------------------ +// +// Let t be a number. It can be uniquely decomposed thus: +// +// t = h*2^26 + l +// such that -2^25 <= l < 2^25 +// +// Let c = (t + 2^25) / 2^26 (rounded down) +// c = (h*2^26 + l + 2^25) / 2^26 (rounded down) +// c = h + (l + 2^25) / 2^26 (rounded down) +// c = h (exactly) +// Because 0 <= l + 2^25 < 2^26 +// +// Let u = t - c*2^26 +// u = h*2^26 + l - h*2^26 +// u = l +// Therefore, -2^25 <= u < 2^25 +// +// Additionally, if |t| < x, then |h| < x/2^26 (rounded down) +// +// Notations: +// - In C, 1<<25 means 2^25. +// - In C, x>>25 means floor(x / (2^25)). +// - All of the above applies with 25 & 24 as well as 26 & 25. +// +// +// Note on negative right shifts +// ----------------------------- +// +// In C, x >> n, where x is a negative integer, is implementation +// defined. In practice, all platforms do arithmetic shift, which is +// equivalent to division by 2^26, rounded down. Some compilers, like +// GCC, even guarantee it. +// +// If we ever stumble upon a platform that does not propagate the sign +// bit (we won't), visible failures will show at the slightest test, and +// the signed shifts can be replaced by the following: +// +// typedef struct { i64 x:39; } s25; +// typedef struct { i64 x:38; } s26; +// i64 shift25(i64 x) { s25 s; s.x = ((u64)x)>>25; return s.x; } +// i64 shift26(i64 x) { s26 s; s.x = ((u64)x)>>26; return s.x; } +// +// Current compilers cannot optimise this, causing a 30% drop in +// performance. Fairly expensive for something that never happens. +// +// +// Precondition +// ------------ +// +// |t0| < 2^63 +// |t1|..|t9| < 2^62 +// +// Algorithm +// --------- +// c = t0 + 2^25 / 2^26 -- |c| <= 2^36 +// t0 -= c * 2^26 -- |t0| <= 2^25 +// t1 += c -- |t1| <= 2^63 +// +// c = t4 + 2^25 / 2^26 -- |c| <= 2^36 +// t4 -= c * 2^26 -- |t4| <= 2^25 +// t5 += c -- |t5| <= 2^63 +// +// c = t1 + 2^24 / 2^25 -- |c| <= 2^38 +// t1 -= c * 2^25 -- |t1| <= 2^24 +// t2 += c -- |t2| <= 2^63 +// +// c = t5 + 2^24 / 2^25 -- |c| <= 2^38 +// t5 -= c * 2^25 -- |t5| <= 2^24 +// t6 += c -- |t6| <= 2^63 +// +// c = t2 + 2^25 / 2^26 -- |c| <= 2^37 +// t2 -= c * 2^26 -- |t2| <= 2^25 < 1.1 * 2^25 (final t2) +// t3 += c -- |t3| <= 2^63 +// +// c = t6 + 2^25 / 2^26 -- |c| <= 2^37 +// t6 -= c * 2^26 -- |t6| <= 2^25 < 1.1 * 2^25 (final t6) +// t7 += c -- |t7| <= 2^63 +// +// c = t3 + 2^24 / 2^25 -- |c| <= 2^38 +// t3 -= c * 2^25 -- |t3| <= 2^24 < 1.1 * 2^24 (final t3) +// t4 += c -- |t4| <= 2^25 + 2^38 < 2^39 +// +// c = t7 + 2^24 / 2^25 -- |c| <= 2^38 +// t7 -= c * 2^25 -- |t7| <= 2^24 < 1.1 * 2^24 (final t7) +// t8 += c -- |t8| <= 2^63 +// +// c = t4 + 2^25 / 2^26 -- |c| <= 2^13 +// t4 -= c * 2^26 -- |t4| <= 2^25 < 1.1 * 2^25 (final t4) +// t5 += c -- |t5| <= 2^24 + 2^13 < 1.1 * 2^24 (final t5) +// +// c = t8 + 2^25 / 2^26 -- |c| <= 2^37 +// t8 -= c * 2^26 -- |t8| <= 2^25 < 1.1 * 2^25 (final t8) +// t9 += c -- |t9| <= 2^63 +// +// c = t9 + 2^24 / 2^25 -- |c| <= 2^38 +// t9 -= c * 2^25 -- |t9| <= 2^24 < 1.1 * 2^24 (final t9) +// t0 += c * 19 -- |t0| <= 2^25 + 2^38*19 < 2^44 +// +// c = t0 + 2^25 / 2^26 -- |c| <= 2^18 +// t0 -= c * 2^26 -- |t0| <= 2^25 < 1.1 * 2^25 (final t0) +// t1 += c -- |t1| <= 2^24 + 2^18 < 1.1 * 2^24 (final t1) +// +// Postcondition +// ------------- +// |t0|, |t2|, |t4|, |t6|, |t8| < 1.1 * 2^25 +// |t1|, |t3|, |t5|, |t7|, |t9| < 1.1 * 2^24 +#define FE_CARRY \ + i64 c; \ + c = (t0 + ((i64)1<<25)) >> 26; t0 -= c * ((i64)1 << 26); t1 += c; \ + c = (t4 + ((i64)1<<25)) >> 26; t4 -= c * ((i64)1 << 26); t5 += c; \ + c = (t1 + ((i64)1<<24)) >> 25; t1 -= c * ((i64)1 << 25); t2 += c; \ + c = (t5 + ((i64)1<<24)) >> 25; t5 -= c * ((i64)1 << 25); t6 += c; \ + c = (t2 + ((i64)1<<25)) >> 26; t2 -= c * ((i64)1 << 26); t3 += c; \ + c = (t6 + ((i64)1<<25)) >> 26; t6 -= c * ((i64)1 << 26); t7 += c; \ + c = (t3 + ((i64)1<<24)) >> 25; t3 -= c * ((i64)1 << 25); t4 += c; \ + c = (t7 + ((i64)1<<24)) >> 25; t7 -= c * ((i64)1 << 25); t8 += c; \ + c = (t4 + ((i64)1<<25)) >> 26; t4 -= c * ((i64)1 << 26); t5 += c; \ + c = (t8 + ((i64)1<<25)) >> 26; t8 -= c * ((i64)1 << 26); t9 += c; \ + c = (t9 + ((i64)1<<24)) >> 25; t9 -= c * ((i64)1 << 25); t0 += c * 19; \ + c = (t0 + ((i64)1<<25)) >> 26; t0 -= c * ((i64)1 << 26); t1 += c; \ + h[0]=(i32)t0; h[1]=(i32)t1; h[2]=(i32)t2; h[3]=(i32)t3; h[4]=(i32)t4; \ + h[5]=(i32)t5; h[6]=(i32)t6; h[7]=(i32)t7; h[8]=(i32)t8; h[9]=(i32)t9 + +static void fe_frombytes(fe h, const u8 s[32]) +{ + i64 t0 = load32_le(s); // t0 < 2^32 + i64 t1 = load24_le(s + 4) << 6; // t1 < 2^30 + i64 t2 = load24_le(s + 7) << 5; // t2 < 2^29 + i64 t3 = load24_le(s + 10) << 3; // t3 < 2^27 + i64 t4 = load24_le(s + 13) << 2; // t4 < 2^26 + i64 t5 = load32_le(s + 16); // t5 < 2^32 + i64 t6 = load24_le(s + 20) << 7; // t6 < 2^31 + i64 t7 = load24_le(s + 23) << 5; // t7 < 2^29 + i64 t8 = load24_le(s + 26) << 4; // t8 < 2^28 + i64 t9 = (load24_le(s + 29) & 0x7fffff) << 2; // t9 < 2^25 + FE_CARRY; // Carry recondition OK +} + +// Precondition +// |h[0]|, |h[2]|, |h[4]|, |h[6]|, |h[8]| < 1.1 * 2^25 +// |h[1]|, |h[3]|, |h[5]|, |h[7]|, |h[9]| < 1.1 * 2^24 +// +// Therefore, |h| < 2^255-19 +// There are two possibilities: +// +// - If h is positive, all we need to do is reduce its individual +// limbs down to their tight positive range. +// - If h is negative, we also need to add 2^255-19 to it. +// Or just remove 19 and chop off any excess bit. +static void fe_tobytes(u8 s[32], const fe h) +{ + i32 t[10]; + COPY(t, h, 10); + i32 q = (19 * t[9] + (((i32) 1) << 24)) >> 25; + // |t9| < 1.1 * 2^24 + // -1.1 * 2^24 < t9 < 1.1 * 2^24 + // -21 * 2^24 < 19 * t9 < 21 * 2^24 + // -2^29 < 19 * t9 + 2^24 < 2^29 + // -2^29 / 2^25 < (19 * t9 + 2^24) / 2^25 < 2^29 / 2^25 + // -16 < (19 * t9 + 2^24) / 2^25 < 16 + FOR (i, 0, 5) { + q += t[2*i ]; q >>= 26; // q = 0 or -1 + q += t[2*i+1]; q >>= 25; // q = 0 or -1 + } + // q = 0 iff h >= 0 + // q = -1 iff h < 0 + // Adding q * 19 to h reduces h to its proper range. + q *= 19; // Shift carry back to the beginning + FOR (i, 0, 5) { + t[i*2 ] += q; q = t[i*2 ] >> 26; t[i*2 ] -= q * ((i32)1 << 26); + t[i*2+1] += q; q = t[i*2+1] >> 25; t[i*2+1] -= q * ((i32)1 << 25); + } + // h is now fully reduced, and q represents the excess bit. + + store32_le(s + 0, ((u32)t[0] >> 0) | ((u32)t[1] << 26)); + store32_le(s + 4, ((u32)t[1] >> 6) | ((u32)t[2] << 19)); + store32_le(s + 8, ((u32)t[2] >> 13) | ((u32)t[3] << 13)); + store32_le(s + 12, ((u32)t[3] >> 19) | ((u32)t[4] << 6)); + store32_le(s + 16, ((u32)t[5] >> 0) | ((u32)t[6] << 25)); + store32_le(s + 20, ((u32)t[6] >> 7) | ((u32)t[7] << 19)); + store32_le(s + 24, ((u32)t[7] >> 13) | ((u32)t[8] << 12)); + store32_le(s + 28, ((u32)t[8] >> 20) | ((u32)t[9] << 6)); + + WIPE_BUFFER(t); +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// |g0|, |g2|, |g4|, |g6|, |g8| < 1.65 * 2^26 +// |g1|, |g3|, |g5|, |g7|, |g9| < 1.65 * 2^25 +static void fe_mul_small(fe h, const fe f, i32 g) +{ + i64 t0 = f[0] * (i64) g; i64 t1 = f[1] * (i64) g; + i64 t2 = f[2] * (i64) g; i64 t3 = f[3] * (i64) g; + i64 t4 = f[4] * (i64) g; i64 t5 = f[5] * (i64) g; + i64 t6 = f[6] * (i64) g; i64 t7 = f[7] * (i64) g; + i64 t8 = f[8] * (i64) g; i64 t9 = f[9] * (i64) g; + // |t0|, |t2|, |t4|, |t6|, |t8| < 1.65 * 2^26 * 2^31 < 2^58 + // |t1|, |t3|, |t5|, |t7|, |t9| < 1.65 * 2^25 * 2^31 < 2^57 + + FE_CARRY; // Carry precondition OK +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// |g0|, |g2|, |g4|, |g6|, |g8| < 1.65 * 2^26 +// |g1|, |g3|, |g5|, |g7|, |g9| < 1.65 * 2^25 +static void fe_mul(fe h, const fe f, const fe g) +{ + // Everything is unrolled and put in temporary variables. + // We could roll the loop, but that would make curve25519 twice as slow. + i32 f0 = f[0]; i32 f1 = f[1]; i32 f2 = f[2]; i32 f3 = f[3]; i32 f4 = f[4]; + i32 f5 = f[5]; i32 f6 = f[6]; i32 f7 = f[7]; i32 f8 = f[8]; i32 f9 = f[9]; + i32 g0 = g[0]; i32 g1 = g[1]; i32 g2 = g[2]; i32 g3 = g[3]; i32 g4 = g[4]; + i32 g5 = g[5]; i32 g6 = g[6]; i32 g7 = g[7]; i32 g8 = g[8]; i32 g9 = g[9]; + i32 F1 = f1*2; i32 F3 = f3*2; i32 F5 = f5*2; i32 F7 = f7*2; i32 F9 = f9*2; + i32 G1 = g1*19; i32 G2 = g2*19; i32 G3 = g3*19; + i32 G4 = g4*19; i32 G5 = g5*19; i32 G6 = g6*19; + i32 G7 = g7*19; i32 G8 = g8*19; i32 G9 = g9*19; + // |F1|, |F3|, |F5|, |F7|, |F9| < 1.65 * 2^26 + // |G0|, |G2|, |G4|, |G6|, |G8| < 2^31 + // |G1|, |G3|, |G5|, |G7|, |G9| < 2^30 + + i64 t0 = f0*(i64)g0 + F1*(i64)G9 + f2*(i64)G8 + F3*(i64)G7 + f4*(i64)G6 + + F5*(i64)G5 + f6*(i64)G4 + F7*(i64)G3 + f8*(i64)G2 + F9*(i64)G1; + i64 t1 = f0*(i64)g1 + f1*(i64)g0 + f2*(i64)G9 + f3*(i64)G8 + f4*(i64)G7 + + f5*(i64)G6 + f6*(i64)G5 + f7*(i64)G4 + f8*(i64)G3 + f9*(i64)G2; + i64 t2 = f0*(i64)g2 + F1*(i64)g1 + f2*(i64)g0 + F3*(i64)G9 + f4*(i64)G8 + + F5*(i64)G7 + f6*(i64)G6 + F7*(i64)G5 + f8*(i64)G4 + F9*(i64)G3; + i64 t3 = f0*(i64)g3 + f1*(i64)g2 + f2*(i64)g1 + f3*(i64)g0 + f4*(i64)G9 + + f5*(i64)G8 + f6*(i64)G7 + f7*(i64)G6 + f8*(i64)G5 + f9*(i64)G4; + i64 t4 = f0*(i64)g4 + F1*(i64)g3 + f2*(i64)g2 + F3*(i64)g1 + f4*(i64)g0 + + F5*(i64)G9 + f6*(i64)G8 + F7*(i64)G7 + f8*(i64)G6 + F9*(i64)G5; + i64 t5 = f0*(i64)g5 + f1*(i64)g4 + f2*(i64)g3 + f3*(i64)g2 + f4*(i64)g1 + + f5*(i64)g0 + f6*(i64)G9 + f7*(i64)G8 + f8*(i64)G7 + f9*(i64)G6; + i64 t6 = f0*(i64)g6 + F1*(i64)g5 + f2*(i64)g4 + F3*(i64)g3 + f4*(i64)g2 + + F5*(i64)g1 + f6*(i64)g0 + F7*(i64)G9 + f8*(i64)G8 + F9*(i64)G7; + i64 t7 = f0*(i64)g7 + f1*(i64)g6 + f2*(i64)g5 + f3*(i64)g4 + f4*(i64)g3 + + f5*(i64)g2 + f6*(i64)g1 + f7*(i64)g0 + f8*(i64)G9 + f9*(i64)G8; + i64 t8 = f0*(i64)g8 + F1*(i64)g7 + f2*(i64)g6 + F3*(i64)g5 + f4*(i64)g4 + + F5*(i64)g3 + f6*(i64)g2 + F7*(i64)g1 + f8*(i64)g0 + F9*(i64)G9; + i64 t9 = f0*(i64)g9 + f1*(i64)g8 + f2*(i64)g7 + f3*(i64)g6 + f4*(i64)g5 + + f5*(i64)g4 + f6*(i64)g3 + f7*(i64)g2 + f8*(i64)g1 + f9*(i64)g0; + // t0 < 0.67 * 2^61 + // t1 < 0.41 * 2^61 + // t2 < 0.52 * 2^61 + // t3 < 0.32 * 2^61 + // t4 < 0.38 * 2^61 + // t5 < 0.22 * 2^61 + // t6 < 0.23 * 2^61 + // t7 < 0.13 * 2^61 + // t8 < 0.09 * 2^61 + // t9 < 0.03 * 2^61 + + FE_CARRY; // Everything below 2^62, Carry precondition OK +} + +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// Note: we could use fe_mul() for this, but this is significantly faster +static void fe_sq(fe h, const fe f) +{ + i32 f0 = f[0]; i32 f1 = f[1]; i32 f2 = f[2]; i32 f3 = f[3]; i32 f4 = f[4]; + i32 f5 = f[5]; i32 f6 = f[6]; i32 f7 = f[7]; i32 f8 = f[8]; i32 f9 = f[9]; + i32 f0_2 = f0*2; i32 f1_2 = f1*2; i32 f2_2 = f2*2; i32 f3_2 = f3*2; + i32 f4_2 = f4*2; i32 f5_2 = f5*2; i32 f6_2 = f6*2; i32 f7_2 = f7*2; + i32 f5_38 = f5*38; i32 f6_19 = f6*19; i32 f7_38 = f7*38; + i32 f8_19 = f8*19; i32 f9_38 = f9*38; + // |f0_2| , |f2_2| , |f4_2| , |f6_2| , |f8_2| < 1.65 * 2^27 + // |f1_2| , |f3_2| , |f5_2| , |f7_2| , |f9_2| < 1.65 * 2^26 + // |f5_38|, |f6_19|, |f7_38|, |f8_19|, |f9_38| < 2^31 + + i64 t0 = f0 *(i64)f0 + f1_2*(i64)f9_38 + f2_2*(i64)f8_19 + + f3_2*(i64)f7_38 + f4_2*(i64)f6_19 + f5 *(i64)f5_38; + i64 t1 = f0_2*(i64)f1 + f2 *(i64)f9_38 + f3_2*(i64)f8_19 + + f4 *(i64)f7_38 + f5_2*(i64)f6_19; + i64 t2 = f0_2*(i64)f2 + f1_2*(i64)f1 + f3_2*(i64)f9_38 + + f4_2*(i64)f8_19 + f5_2*(i64)f7_38 + f6 *(i64)f6_19; + i64 t3 = f0_2*(i64)f3 + f1_2*(i64)f2 + f4 *(i64)f9_38 + + f5_2*(i64)f8_19 + f6 *(i64)f7_38; + i64 t4 = f0_2*(i64)f4 + f1_2*(i64)f3_2 + f2 *(i64)f2 + + f5_2*(i64)f9_38 + f6_2*(i64)f8_19 + f7 *(i64)f7_38; + i64 t5 = f0_2*(i64)f5 + f1_2*(i64)f4 + f2_2*(i64)f3 + + f6 *(i64)f9_38 + f7_2*(i64)f8_19; + i64 t6 = f0_2*(i64)f6 + f1_2*(i64)f5_2 + f2_2*(i64)f4 + + f3_2*(i64)f3 + f7_2*(i64)f9_38 + f8 *(i64)f8_19; + i64 t7 = f0_2*(i64)f7 + f1_2*(i64)f6 + f2_2*(i64)f5 + + f3_2*(i64)f4 + f8 *(i64)f9_38; + i64 t8 = f0_2*(i64)f8 + f1_2*(i64)f7_2 + f2_2*(i64)f6 + + f3_2*(i64)f5_2 + f4 *(i64)f4 + f9 *(i64)f9_38; + i64 t9 = f0_2*(i64)f9 + f1_2*(i64)f8 + f2_2*(i64)f7 + + f3_2*(i64)f6 + f4 *(i64)f5_2; + // t0 < 0.67 * 2^61 + // t1 < 0.41 * 2^61 + // t2 < 0.52 * 2^61 + // t3 < 0.32 * 2^61 + // t4 < 0.38 * 2^61 + // t5 < 0.22 * 2^61 + // t6 < 0.23 * 2^61 + // t7 < 0.13 * 2^61 + // t8 < 0.09 * 2^61 + // t9 < 0.03 * 2^61 + + FE_CARRY; +} + +// h = 2 * (f^2) +// +// Precondition +// ------------- +// |f0|, |f2|, |f4|, |f6|, |f8| < 1.65 * 2^26 +// |f1|, |f3|, |f5|, |f7|, |f9| < 1.65 * 2^25 +// +// Note: we could implement fe_sq2() by copying fe_sq(), multiplying +// each limb by 2, *then* perform the carry. This saves one carry. +// However, doing so with the stated preconditions does not work (t2 +// would overflow). There are 3 ways to solve this: +// +// 1. Show that t2 actually never overflows (it really does not). +// 2. Accept an additional carry, at a small lost of performance. +// 3. Make sure the input of fe_sq2() is freshly carried. +// +// SUPERCOP ref10 relies on (1). +// Monocypher chose (2) and (3), mostly to save code. +static void fe_sq2(fe h, const fe f) +{ + fe_sq(h, f); + fe_mul_small(h, h, 2); +} + +// This could be simplified, but it would be slower +static void fe_pow22523(fe out, const fe z) +{ + fe t0, t1, t2; + fe_sq(t0, z); + fe_sq(t1,t0); fe_sq(t1, t1); fe_mul(t1, z, t1); + fe_mul(t0, t0, t1); + fe_sq(t0, t0); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 5) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 10) fe_sq(t1, t1); fe_mul(t1, t1, t0); + fe_sq(t2, t1); FOR (i, 1, 20) fe_sq(t2, t2); fe_mul(t1, t2, t1); + fe_sq(t1, t1); FOR (i, 1, 10) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t1, t0); FOR (i, 1, 50) fe_sq(t1, t1); fe_mul(t1, t1, t0); + fe_sq(t2, t1); FOR (i, 1, 100) fe_sq(t2, t2); fe_mul(t1, t2, t1); + fe_sq(t1, t1); FOR (i, 1, 50) fe_sq(t1, t1); fe_mul(t0, t1, t0); + fe_sq(t0, t0); FOR (i, 1, 2) fe_sq(t0, t0); fe_mul(out, t0, z); + WIPE_BUFFER(t0); + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); +} + +// Inverting means multiplying by 2^255 - 21 +// 2^255 - 21 = (2^252 - 3) * 8 + 3 +// So we reuse the multiplication chain of fe_pow22523 +static void fe_invert(fe out, const fe z) +{ + fe tmp; + fe_pow22523(tmp, z); + // tmp2^8 * z^3 + fe_sq(tmp, tmp); // 0 + fe_sq(tmp, tmp); fe_mul(tmp, tmp, z); // 1 + fe_sq(tmp, tmp); fe_mul(out, tmp, z); // 1 + WIPE_BUFFER(tmp); +} + +// Parity check. Returns 0 if even, 1 if odd +static int fe_isodd(const fe f) +{ + u8 s[32]; + fe_tobytes(s, f); + u8 isodd = s[0] & 1; + WIPE_BUFFER(s); + return isodd; +} + +// Returns 1 if equal, 0 if not equal +static int fe_isequal(const fe f, const fe g) +{ + u8 fs[32]; + u8 gs[32]; + fe_tobytes(fs, f); + fe_tobytes(gs, g); + int isdifferent = crypto_verify32(fs, gs); + WIPE_BUFFER(fs); + WIPE_BUFFER(gs); + return 1 + isdifferent; +} + +// Inverse square root. +// Returns true if x is a non zero square, false otherwise. +// After the call: +// isr = sqrt(1/x) if x is non-zero square. +// isr = sqrt(sqrt(-1)/x) if x is not a square. +// isr = 0 if x is zero. +// We do not guarantee the sign of the square root. +// +// Notes: +// Let quartic = x^((p-1)/4) +// +// x^((p-1)/2) = chi(x) +// quartic^2 = chi(x) +// quartic = sqrt(chi(x)) +// quartic = 1 or -1 or sqrt(-1) or -sqrt(-1) +// +// Note that x is a square if quartic is 1 or -1 +// There are 4 cases to consider: +// +// if quartic = 1 (x is a square) +// then x^((p-1)/4) = 1 +// x^((p-5)/4) * x = 1 +// x^((p-5)/4) = 1/x +// x^((p-5)/8) = sqrt(1/x) or -sqrt(1/x) +// +// if quartic = -1 (x is a square) +// then x^((p-1)/4) = -1 +// x^((p-5)/4) * x = -1 +// x^((p-5)/4) = -1/x +// x^((p-5)/8) = sqrt(-1) / sqrt(x) +// x^((p-5)/8) * sqrt(-1) = sqrt(-1)^2 / sqrt(x) +// x^((p-5)/8) * sqrt(-1) = -1/sqrt(x) +// x^((p-5)/8) * sqrt(-1) = -sqrt(1/x) or sqrt(1/x) +// +// if quartic = sqrt(-1) (x is not a square) +// then x^((p-1)/4) = sqrt(-1) +// x^((p-5)/4) * x = sqrt(-1) +// x^((p-5)/4) = sqrt(-1)/x +// x^((p-5)/8) = sqrt(sqrt(-1)/x) or -sqrt(sqrt(-1)/x) +// +// Note that the product of two non-squares is always a square: +// For any non-squares a and b, chi(a) = -1 and chi(b) = -1. +// Since chi(x) = x^((p-1)/2), chi(a)*chi(b) = chi(a*b) = 1. +// Therefore a*b is a square. +// +// Since sqrt(-1) and x are both non-squares, their product is a +// square, and we can compute their square root. +// +// if quartic = -sqrt(-1) (x is not a square) +// then x^((p-1)/4) = -sqrt(-1) +// x^((p-5)/4) * x = -sqrt(-1) +// x^((p-5)/4) = -sqrt(-1)/x +// x^((p-5)/8) = sqrt(-sqrt(-1)/x) +// x^((p-5)/8) = sqrt( sqrt(-1)/x) * sqrt(-1) +// x^((p-5)/8) * sqrt(-1) = sqrt( sqrt(-1)/x) * sqrt(-1)^2 +// x^((p-5)/8) * sqrt(-1) = sqrt( sqrt(-1)/x) * -1 +// x^((p-5)/8) * sqrt(-1) = -sqrt(sqrt(-1)/x) or sqrt(sqrt(-1)/x) +static int invsqrt(fe isr, const fe x) +{ + fe check, quartic; + fe_copy(check, x); + fe_pow22523(isr, check); + fe_sq (quartic, isr); + fe_mul(quartic, quartic, check); + fe_1 (check); int p1 = fe_isequal(quartic, check); + fe_neg(check, check ); int m1 = fe_isequal(quartic, check); + fe_neg(check, sqrtm1); int ms = fe_isequal(quartic, check); + fe_mul(check, isr, sqrtm1); + fe_ccopy(isr, check, m1 | ms); + WIPE_BUFFER(quartic); + WIPE_BUFFER(check); + return p1 | m1; +} + +// trim a scalar for scalar multiplication +static void trim_scalar(u8 scalar[32]) +{ + scalar[ 0] &= 248; + scalar[31] &= 127; + scalar[31] |= 64; +} + +// get bit from scalar at position i +static int scalar_bit(const u8 s[32], int i) +{ + if (i < 0) { return 0; } // handle -1 for sliding windows + return (s[i>>3] >> (i&7)) & 1; +} + +/////////////// +/// X-25519 /// Taken from SUPERCOP's ref10 implementation. +/////////////// +static void scalarmult(u8 q[32], const u8 scalar[32], const u8 p[32], + int nb_bits) +{ + // computes the scalar product + fe x1; + fe_frombytes(x1, p); + + // computes the actual scalar product (the result is in x2 and z2) + fe x2, z2, x3, z3, t0, t1; + // Montgomery ladder + // In projective coordinates, to avoid divisions: x = X / Z + // We don't care about the y coordinate, it's only 1 bit of information + fe_1(x2); fe_0(z2); // "zero" point + fe_copy(x3, x1); fe_1(z3); // "one" point + int swap = 0; + for (int pos = nb_bits-1; pos >= 0; --pos) { + // constant time conditional swap before ladder step + int b = scalar_bit(scalar, pos); + swap ^= b; // xor trick avoids swapping at the end of the loop + fe_cswap(x2, x3, swap); + fe_cswap(z2, z3, swap); + swap = b; // anticipates one last swap after the loop + + // Montgomery ladder step: replaces (P2, P3) by (P2*2, P2+P3) + // with differential addition + fe_sub(t0, x3, z3); + fe_sub(t1, x2, z2); + fe_add(x2, x2, z2); + fe_add(z2, x3, z3); + fe_mul(z3, t0, x2); + fe_mul(z2, z2, t1); + fe_sq (t0, t1 ); + fe_sq (t1, x2 ); + fe_add(x3, z3, z2); + fe_sub(z2, z3, z2); + fe_mul(x2, t1, t0); + fe_sub(t1, t1, t0); + fe_sq (z2, z2 ); + fe_mul_small(z3, t1, 121666); + fe_sq (x3, x3 ); + fe_add(t0, t0, z3); + fe_mul(z3, x1, z2); + fe_mul(z2, t1, t0); + } + // last swap is necessary to compensate for the xor trick + // Note: after this swap, P3 == P2 + P1. + fe_cswap(x2, x3, swap); + fe_cswap(z2, z3, swap); + + // normalises the coordinates: x == X / Z + fe_invert(z2, z2); + fe_mul(x2, x2, z2); + fe_tobytes(q, x2); + + WIPE_BUFFER(x1); + WIPE_BUFFER(x2); WIPE_BUFFER(z2); WIPE_BUFFER(t0); + WIPE_BUFFER(x3); WIPE_BUFFER(z3); WIPE_BUFFER(t1); +} + +void crypto_x25519(u8 raw_shared_secret[32], + const u8 your_secret_key [32], + const u8 their_public_key [32]) +{ + // restrict the possible scalar values + u8 e[32]; + COPY(e, your_secret_key, 32); + trim_scalar(e); + scalarmult(raw_shared_secret, e, their_public_key, 255); + WIPE_BUFFER(e); +} + +void crypto_x25519_public_key(u8 public_key[32], + const u8 secret_key[32]) +{ + static const u8 base_point[32] = {9}; + crypto_x25519(public_key, secret_key, base_point); +} + +/////////////////////////// +/// Arithmetic modulo L /// +/////////////////////////// +static const u32 L[8] = {0x5cf5d3ed, 0x5812631a, 0xa2f79cd6, 0x14def9de, + 0x00000000, 0x00000000, 0x00000000, 0x10000000,}; + +// p = a*b + p +static void multiply(u32 p[16], const u32 a[8], const u32 b[8]) +{ + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8) { + carry += p[i+j] + (u64)a[i] * b[j]; + p[i+j] = (u32)carry; + carry >>= 32; + } + p[i+8] = (u32)carry; + } +} + +static int is_above_l(const u32 x[8]) +{ + // We work with L directly, in a 2's complement encoding + // (-L == ~L + 1) + u64 carry = 1; + FOR (i, 0, 8) { + carry += (u64)x[i] + ~L[i]; + carry >>= 32; + } + return carry; +} + +// Final reduction modulo L, by conditionally removing L. +// if x < l , then r = x +// if l <= x 2*l, then r = x-l +// otherwise the result will be wrong +static void remove_l(u32 r[8], const u32 x[8]) +{ + u64 carry = is_above_l(x); + u32 mask = ~(u32)carry + 1; // carry == 0 or 1 + FOR (i, 0, 8) { + carry += (u64)x[i] + (~L[i] & mask); + r[i] = (u32)carry; + carry >>= 32; + } +} + +// Full reduction modulo L (Barrett reduction) +static void mod_l(u8 reduced[32], const u32 x[16]) +{ + static const u32 r[9] = {0x0a2c131b,0xed9ce5a3,0x086329a7,0x2106215d, + 0xffffffeb,0xffffffff,0xffffffff,0xffffffff,0xf,}; + // xr = x * r + u32 xr[25] = {0}; + FOR (i, 0, 9) { + u64 carry = 0; + FOR (j, 0, 16) { + carry += xr[i+j] + (u64)r[i] * x[j]; + xr[i+j] = (u32)carry; + carry >>= 32; + } + xr[i+16] = (u32)carry; + } + // xr = floor(xr / 2^512) * L + // Since the result is guaranteed to be below 2*L, + // it is enough to only compute the first 256 bits. + // The division is performed by saying xr[i+16]. (16 * 32 = 512) + ZERO(xr, 8); + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8-i) { + carry += xr[i+j] + (u64)xr[i+16] * L[j]; + xr[i+j] = (u32)carry; + carry >>= 32; + } + } + // xr = x - xr + u64 carry = 1; + FOR (i, 0, 8) { + carry += (u64)x[i] + ~xr[i]; + xr[i] = (u32)carry; + carry >>= 32; + } + // Final reduction modulo L (conditional subtraction) + remove_l(xr, xr); + store32_le_buf(reduced, xr, 8); + + WIPE_BUFFER(xr); +} + +static void reduce(u8 r[64]) +{ + u32 x[16]; + load32_le_buf(x, r, 16); + mod_l(r, x); + WIPE_BUFFER(x); +} + +// r = (a * b) + c +static void mul_add(u8 r[32], const u8 a[32], const u8 b[32], const u8 c[32]) +{ + u32 A[8]; load32_le_buf(A, a, 8); + u32 B[8]; load32_le_buf(B, b, 8); + u32 p[16]; + load32_le_buf(p, c, 8); + ZERO(p + 8, 8); + multiply(p, A, B); + mod_l(r, p); + WIPE_BUFFER(p); + WIPE_BUFFER(A); + WIPE_BUFFER(B); +} + +/////////////// +/// Ed25519 /// +/////////////// + +// Point (group element, ge) in a twisted Edwards curve, +// in extended projective coordinates. +// ge : x = X/Z, y = Y/Z, T = XY/Z +// ge_cached : Yp = X+Y, Ym = X-Y, T2 = T*D2 +// ge_precomp: Z = 1 +typedef struct { fe X; fe Y; fe Z; fe T; } ge; +typedef struct { fe Yp; fe Ym; fe Z; fe T2; } ge_cached; +typedef struct { fe Yp; fe Ym; fe T2; } ge_precomp; + +static void ge_zero(ge *p) +{ + fe_0(p->X); + fe_1(p->Y); + fe_1(p->Z); + fe_0(p->T); +} + +static void ge_tobytes(u8 s[32], const ge *h) +{ + fe recip, x, y; + fe_invert(recip, h->Z); + fe_mul(x, h->X, recip); + fe_mul(y, h->Y, recip); + fe_tobytes(s, y); + s[31] ^= fe_isodd(x) << 7; + + WIPE_BUFFER(recip); + WIPE_BUFFER(x); + WIPE_BUFFER(y); +} + +// h = s, where s is a point encoded in 32 bytes +// +// Variable time! Inputs must not be secret! +// => Use only to *check* signatures. +// +// From the specifications: +// The encoding of s contains y and the sign of x +// x = sqrt((y^2 - 1) / (d*y^2 + 1)) +// In extended coordinates: +// X = x, Y = y, Z = 1, T = x*y +// +// Note that num * den is a square iff num / den is a square +// If num * den is not a square, the point was not on the curve. +// From the above: +// Let num = y^2 - 1 +// Let den = d*y^2 + 1 +// x = sqrt((y^2 - 1) / (d*y^2 + 1)) +// x = sqrt(num / den) +// x = sqrt(num^2 / (num * den)) +// x = num * sqrt(1 / (num * den)) +// +// Therefore, we can just compute: +// num = y^2 - 1 +// den = d*y^2 + 1 +// isr = invsqrt(num * den) // abort if not square +// x = num * isr +// Finally, negate x if its sign is not as specified. +static int ge_frombytes_vartime(ge *h, const u8 s[32]) +{ + fe_frombytes(h->Y, s); + fe_1(h->Z); + fe_sq (h->T, h->Y); // t = y^2 + fe_mul(h->X, h->T, d ); // x = d*y^2 + fe_sub(h->T, h->T, h->Z); // t = y^2 - 1 + fe_add(h->X, h->X, h->Z); // x = d*y^2 + 1 + fe_mul(h->X, h->T, h->X); // x = (y^2 - 1) * (d*y^2 + 1) + int is_square = invsqrt(h->X, h->X); + if (!is_square) { + return -1; // Not on the curve, abort + } + fe_mul(h->X, h->T, h->X); // x = sqrt((y^2 - 1) / (d*y^2 + 1)) + if (fe_isodd(h->X) != (s[31] >> 7)) { + fe_neg(h->X, h->X); + } + fe_mul(h->T, h->X, h->Y); + return 0; +} + +static void ge_cache(ge_cached *c, const ge *p) +{ + fe_add (c->Yp, p->Y, p->X); + fe_sub (c->Ym, p->Y, p->X); + fe_copy(c->Z , p->Z ); + fe_mul (c->T2, p->T, D2 ); +} + +// Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_add(ge *s, const ge *p, const ge_cached *q) +{ + fe a, b; + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Yp); + fe_mul(b , b , q->Ym); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->Z, s->Z, q->Z ); + fe_mul(s->T, p->T, q->T2); + fe_add(a , s->Z, s->T ); + fe_sub(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +// Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_sub(ge *s, const ge *p, const ge_cached *q) +{ + ge_cached neg; + fe_copy(neg.Ym, q->Yp); + fe_copy(neg.Yp, q->Ym); + fe_copy(neg.Z , q->Z ); + fe_neg (neg.T2, q->T2); + ge_add(s, p, &neg); +} + +static void ge_madd(ge *s, const ge *p, const ge_precomp *q, fe a, fe b) +{ + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Yp); + fe_mul(b , b , q->Ym); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->T, p->T, q->T2); + fe_add(a , s->Z, s->T ); + fe_sub(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +static void ge_msub(ge *s, const ge *p, const ge_precomp *q, fe a, fe b) +{ + fe_add(a , p->Y, p->X ); + fe_sub(b , p->Y, p->X ); + fe_mul(a , a , q->Ym); + fe_mul(b , b , q->Yp); + fe_add(s->Y, a , b ); + fe_sub(s->X, a , b ); + + fe_add(s->Z, p->Z, p->Z ); + fe_mul(s->T, p->T, q->T2); + fe_sub(a , s->Z, s->T ); + fe_add(b , s->Z, s->T ); + + fe_mul(s->T, s->X, s->Y); + fe_mul(s->X, s->X, b ); + fe_mul(s->Y, s->Y, a ); + fe_mul(s->Z, a , b ); +} + +static void ge_double(ge *s, const ge *p, ge *q) +{ + fe_sq (q->X, p->X); + fe_sq (q->Y, p->Y); + fe_sq2(q->Z, p->Z); + fe_add(q->T, p->X, p->Y); + fe_sq (s->T, q->T); + fe_add(q->T, q->Y, q->X); + fe_sub(q->Y, q->Y, q->X); + fe_sub(q->X, s->T, q->T); + fe_sub(q->Z, q->Z, q->Y); + + fe_mul(s->X, q->X , q->Z); + fe_mul(s->Y, q->T , q->Y); + fe_mul(s->Z, q->Y , q->Z); + fe_mul(s->T, q->X , q->T); +} + +// 5-bit signed window in cached format (Niels coordinates, Z=1) +static const ge_precomp b_window[8] = { + {{25967493,-14356035,29566456,3660896,-12694345, + 4014787,27544626,-11754271,-6079156,2047605,}, + {-12545711,934262,-2722910,3049990,-727428, + 9406986,12720692,5043384,19500929,-15469378,}, + {-8738181,4489570,9688441,-14785194,10184609, + -12363380,29287919,11864899,-24514362,-4438546,},}, + {{15636291,-9688557,24204773,-7912398,616977, + -16685262,27787600,-14772189,28944400,-1550024,}, + {16568933,4717097,-11556148,-1102322,15682896, + -11807043,16354577,-11775962,7689662,11199574,}, + {30464156,-5976125,-11779434,-15670865,23220365, + 15915852,7512774,10017326,-17749093,-9920357,},}, + {{10861363,11473154,27284546,1981175,-30064349, + 12577861,32867885,14515107,-15438304,10819380,}, + {4708026,6336745,20377586,9066809,-11272109, + 6594696,-25653668,12483688,-12668491,5581306,}, + {19563160,16186464,-29386857,4097519,10237984, + -4348115,28542350,13850243,-23678021,-15815942,},}, + {{5153746,9909285,1723747,-2777874,30523605, + 5516873,19480852,5230134,-23952439,-15175766,}, + {-30269007,-3463509,7665486,10083793,28475525, + 1649722,20654025,16520125,30598449,7715701,}, + {28881845,14381568,9657904,3680757,-20181635, + 7843316,-31400660,1370708,29794553,-1409300,},}, + {{-22518993,-6692182,14201702,-8745502,-23510406, + 8844726,18474211,-1361450,-13062696,13821877,}, + {-6455177,-7839871,3374702,-4740862,-27098617, + -10571707,31655028,-7212327,18853322,-14220951,}, + {4566830,-12963868,-28974889,-12240689,-7602672, + -2830569,-8514358,-10431137,2207753,-3209784,},}, + {{-25154831,-4185821,29681144,7868801,-6854661, + -9423865,-12437364,-663000,-31111463,-16132436,}, + {25576264,-2703214,7349804,-11814844,16472782, + 9300885,3844789,15725684,171356,6466918,}, + {23103977,13316479,9739013,-16149481,817875, + -15038942,8965339,-14088058,-30714912,16193877,},}, + {{-33521811,3180713,-2394130,14003687,-16903474, + -16270840,17238398,4729455,-18074513,9256800,}, + {-25182317,-4174131,32336398,5036987,-21236817, + 11360617,22616405,9761698,-19827198,630305,}, + {-13720693,2639453,-24237460,-7406481,9494427, + -5774029,-6554551,-15960994,-2449256,-14291300,},}, + {{-3151181,-5046075,9282714,6866145,-31907062, + -863023,-18940575,15033784,25105118,-7894876,}, + {-24326370,15950226,-31801215,-14592823,-11662737, + -5090925,1573892,-2625887,2198790,-15804619,}, + {-3099351,10324967,-2241613,7453183,-5446979, + -2735503,-13812022,-16236442,-32461234,-12290683,},}, +}; + +// Incremental sliding windows (left to right) +// Based on Roberto Maria Avanzi[2005] +typedef struct { + i16 next_index; // position of the next signed digit + i8 next_digit; // next signed digit (odd number below 2^window_width) + u8 next_check; // point at which we must check for a new window +} slide_ctx; + +static void slide_init(slide_ctx *ctx, const u8 scalar[32]) +{ + // scalar is guaranteed to be below L, either because we checked (s), + // or because we reduced it modulo L (h_ram). L is under 2^253, so + // so bits 253 to 255 are guaranteed to be zero. No need to test them. + // + // Note however that L is very close to 2^252, so bit 252 is almost + // always zero. If we were to start at bit 251, the tests wouldn't + // catch the off-by-one error (constructing one that does would be + // prohibitively expensive). + // + // We should still check bit 252, though. + int i = 252; + while (i > 0 && scalar_bit(scalar, i) == 0) { + i--; + } + ctx->next_check = (u8)(i + 1); + ctx->next_index = -1; + ctx->next_digit = -1; +} + +static int slide_step(slide_ctx *ctx, int width, int i, const u8 scalar[32]) +{ + if (i == ctx->next_check) { + if (scalar_bit(scalar, i) == scalar_bit(scalar, i - 1)) { + ctx->next_check--; + } else { + // compute digit of next window + int w = MIN(width, i + 1); + int v = -(scalar_bit(scalar, i) << (w-1)); + FOR_T (int, j, 0, w-1) { + v += scalar_bit(scalar, i-(w-1)+j) << j; + } + v += scalar_bit(scalar, i-w); + int lsb = v & (~v + 1); // smallest bit of v + int s = ( ((lsb & 0xAA) != 0) // log2(lsb) + | (((lsb & 0xCC) != 0) << 1) + | (((lsb & 0xF0) != 0) << 2)); + ctx->next_index = (i16)(i-(w-1)+s); + ctx->next_digit = (i8) (v >> s ); + ctx->next_check -= (u8) w; + } + } + return i == ctx->next_index ? ctx->next_digit: 0; +} + +#define P_W_WIDTH 3 // Affects the size of the stack +#define B_W_WIDTH 5 // Affects the size of the binary +#define P_W_SIZE (1<<(P_W_WIDTH-2)) + +// P = [b]B + [p]P, where B is the base point +// +// Variable time! Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static void ge_double_scalarmult_vartime(ge *P, const u8 p[32], const u8 b[32]) +{ + // cache P window for addition + ge_cached cP[P_W_SIZE]; + { + ge P2, tmp; + ge_double(&P2, P, &tmp); + ge_cache(&cP[0], P); + FOR (i, 1, P_W_SIZE) { + ge_add(&tmp, &P2, &cP[i-1]); + ge_cache(&cP[i], &tmp); + } + } + + // Merged double and add ladder, fused with sliding + slide_ctx p_slide; slide_init(&p_slide, p); + slide_ctx b_slide; slide_init(&b_slide, b); + int i = MAX(p_slide.next_check, b_slide.next_check); + ge *sum = P; + ge_zero(sum); + while (i >= 0) { + ge tmp; + ge_double(sum, sum, &tmp); + int p_digit = slide_step(&p_slide, P_W_WIDTH, i, p); + int b_digit = slide_step(&b_slide, B_W_WIDTH, i, b); + if (p_digit > 0) { ge_add(sum, sum, &cP[ p_digit / 2]); } + if (p_digit < 0) { ge_sub(sum, sum, &cP[-p_digit / 2]); } + fe t1, t2; + if (b_digit > 0) { ge_madd(sum, sum, b_window + b_digit/2, t1, t2); } + if (b_digit < 0) { ge_msub(sum, sum, b_window + -b_digit/2, t1, t2); } + i--; + } +} + +// R_check = s[B] - h_ram[pk], where B is the base point +// +// Variable time! Internal buffers are not wiped! Inputs must not be secret! +// => Use only to *check* signatures. +static int ge_r_check(u8 R_check[32], u8 s[32], u8 h_ram[32], u8 pk[32]) +{ + ge A; // not secret, not wiped + u32 s32[8]; // not secret, not wiped + load32_le_buf(s32, s, 8); + if (ge_frombytes_vartime(&A, pk) || // A = pk + is_above_l(s32)) { // prevent s malleability + return -1; + } + fe_neg(A.X, A.X); + fe_neg(A.T, A.T); // A = -pk + ge_double_scalarmult_vartime(&A, h_ram, s); // A = [s]B - [h_ram]pk + ge_tobytes(R_check, &A); // R_check = A + return 0; +} + +// 5-bit signed comb in cached format (Niels coordinates, Z=1) +static const ge_precomp b_comb_low[8] = { + {{-6816601,-2324159,-22559413,124364,18015490, + 8373481,19993724,1979872,-18549925,9085059,}, + {10306321,403248,14839893,9633706,8463310, + -8354981,-14305673,14668847,26301366,2818560,}, + {-22701500,-3210264,-13831292,-2927732,-16326337, + -14016360,12940910,177905,12165515,-2397893,},}, + {{-12282262,-7022066,9920413,-3064358,-32147467, + 2927790,22392436,-14852487,2719975,16402117,}, + {-7236961,-4729776,2685954,-6525055,-24242706, + -15940211,-6238521,14082855,10047669,12228189,}, + {-30495588,-12893761,-11161261,3539405,-11502464, + 16491580,-27286798,-15030530,-7272871,-15934455,},}, + {{17650926,582297,-860412,-187745,-12072900, + -10683391,-20352381,15557840,-31072141,-5019061,}, + {-6283632,-2259834,-4674247,-4598977,-4089240, + 12435688,-31278303,1060251,6256175,10480726,}, + {-13871026,2026300,-21928428,-2741605,-2406664, + -8034988,7355518,15733500,-23379862,7489131,},}, + {{6883359,695140,23196907,9644202,-33430614, + 11354760,-20134606,6388313,-8263585,-8491918,}, + {-7716174,-13605463,-13646110,14757414,-19430591, + -14967316,10359532,-11059670,-21935259,12082603,}, + {-11253345,-15943946,10046784,5414629,24840771, + 8086951,-6694742,9868723,15842692,-16224787,},}, + {{9639399,11810955,-24007778,-9320054,3912937, + -9856959,996125,-8727907,-8919186,-14097242,}, + {7248867,14468564,25228636,-8795035,14346339, + 8224790,6388427,-7181107,6468218,-8720783,}, + {15513115,15439095,7342322,-10157390,18005294, + -7265713,2186239,4884640,10826567,7135781,},}, + {{-14204238,5297536,-5862318,-6004934,28095835, + 4236101,-14203318,1958636,-16816875,3837147,}, + {-5511166,-13176782,-29588215,12339465,15325758, + -15945770,-8813185,11075932,-19608050,-3776283,}, + {11728032,9603156,-4637821,-5304487,-7827751, + 2724948,31236191,-16760175,-7268616,14799772,},}, + {{-28842672,4840636,-12047946,-9101456,-1445464, + 381905,-30977094,-16523389,1290540,12798615,}, + {27246947,-10320914,14792098,-14518944,5302070, + -8746152,-3403974,-4149637,-27061213,10749585,}, + {25572375,-6270368,-15353037,16037944,1146292, + 32198,23487090,9585613,24714571,-1418265,},}, + {{19844825,282124,-17583147,11004019,-32004269, + -2716035,6105106,-1711007,-21010044,14338445,}, + {8027505,8191102,-18504907,-12335737,25173494, + -5923905,15446145,7483684,-30440441,10009108,}, + {-14134701,-4174411,10246585,-14677495,33553567, + -14012935,23366126,15080531,-7969992,7663473,},}, +}; + +static const ge_precomp b_comb_high[8] = { + {{33055887,-4431773,-521787,6654165,951411, + -6266464,-5158124,6995613,-5397442,-6985227,}, + {4014062,6967095,-11977872,3960002,8001989, + 5130302,-2154812,-1899602,-31954493,-16173976,}, + {16271757,-9212948,23792794,731486,-25808309, + -3546396,6964344,-4767590,10976593,10050757,},}, + {{2533007,-4288439,-24467768,-12387405,-13450051, + 14542280,12876301,13893535,15067764,8594792,}, + {20073501,-11623621,3165391,-13119866,13188608, + -11540496,-10751437,-13482671,29588810,2197295,}, + {-1084082,11831693,6031797,14062724,14748428, + -8159962,-20721760,11742548,31368706,13161200,},}, + {{2050412,-6457589,15321215,5273360,25484180, + 124590,-18187548,-7097255,-6691621,-14604792,}, + {9938196,2162889,-6158074,-1711248,4278932, + -2598531,-22865792,-7168500,-24323168,11746309,}, + {-22691768,-14268164,5965485,9383325,20443693, + 5854192,28250679,-1381811,-10837134,13717818,},}, + {{-8495530,16382250,9548884,-4971523,-4491811, + -3902147,6182256,-12832479,26628081,10395408,}, + {27329048,-15853735,7715764,8717446,-9215518, + -14633480,28982250,-5668414,4227628,242148,}, + {-13279943,-7986904,-7100016,8764468,-27276630, + 3096719,29678419,-9141299,3906709,11265498,},}, + {{11918285,15686328,-17757323,-11217300,-27548967, + 4853165,-27168827,6807359,6871949,-1075745,}, + {-29002610,13984323,-27111812,-2713442,28107359, + -13266203,6155126,15104658,3538727,-7513788,}, + {14103158,11233913,-33165269,9279850,31014152, + 4335090,-1827936,4590951,13960841,12787712,},}, + {{1469134,-16738009,33411928,13942824,8092558, + -8778224,-11165065,1437842,22521552,-2792954,}, + {31352705,-4807352,-25327300,3962447,12541566, + -9399651,-27425693,7964818,-23829869,5541287,}, + {-25732021,-6864887,23848984,3039395,-9147354, + 6022816,-27421653,10590137,25309915,-1584678,},}, + {{-22951376,5048948,31139401,-190316,-19542447, + -626310,-17486305,-16511925,-18851313,-12985140,}, + {-9684890,14681754,30487568,7717771,-10829709, + 9630497,30290549,-10531496,-27798994,-13812825,}, + {5827835,16097107,-24501327,12094619,7413972, + 11447087,28057551,-1793987,-14056981,4359312,},}, + {{26323183,2342588,-21887793,-1623758,-6062284, + 2107090,-28724907,9036464,-19618351,-13055189,}, + {-29697200,14829398,-4596333,14220089,-30022969, + 2955645,12094100,-13693652,-5941445,7047569,}, + {-3201977,14413268,-12058324,-16417589,-9035655, + -7224648,9258160,1399236,30397584,-5684634,},}, +}; + +static void lookup_add(ge *p, ge_precomp *tmp_c, fe tmp_a, fe tmp_b, + const ge_precomp comb[8], const u8 scalar[32], int i) +{ + u8 teeth = (u8)((scalar_bit(scalar, i) ) + + (scalar_bit(scalar, i + 32) << 1) + + (scalar_bit(scalar, i + 64) << 2) + + (scalar_bit(scalar, i + 96) << 3)); + u8 high = teeth >> 3; + u8 index = (teeth ^ (high - 1)) & 7; + FOR (j, 0, 8) { + i32 select = 1 & (((j ^ index) - 1) >> 8); + fe_ccopy(tmp_c->Yp, comb[j].Yp, select); + fe_ccopy(tmp_c->Ym, comb[j].Ym, select); + fe_ccopy(tmp_c->T2, comb[j].T2, select); + } + fe_neg(tmp_a, tmp_c->T2); + fe_cswap(tmp_c->T2, tmp_a , high ^ 1); + fe_cswap(tmp_c->Yp, tmp_c->Ym, high ^ 1); + ge_madd(p, p, tmp_c, tmp_a, tmp_b); +} + +// p = [scalar]B, where B is the base point +static void ge_scalarmult_base(ge *p, const u8 scalar[32]) +{ + // twin 4-bits signed combs, from Mike Hamburg's + // Fast and compact elliptic-curve cryptography (2012) + // 1 / 2 modulo L + static const u8 half_mod_L[32] = { + 247,233,122,46,141,49,9,44,107,206,123,81,239,124,111,10, + 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,8, }; + // (2^256 - 1) / 2 modulo L + static const u8 half_ones[32] = { + 142,74,204,70,186,24,118,107,184,231,190,57,250,173,119,99, + 255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,7, }; + + // All bits set form: 1 means 1, 0 means -1 + u8 s_scalar[32]; + mul_add(s_scalar, scalar, half_mod_L, half_ones); + + // Double and add ladder + fe tmp_a, tmp_b; // temporaries for addition + ge_precomp tmp_c; // temporary for comb lookup + ge tmp_d; // temporary for doubling + fe_1(tmp_c.Yp); + fe_1(tmp_c.Ym); + fe_0(tmp_c.T2); + + // Save a double on the first iteration + ge_zero(p); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_low , s_scalar, 31); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_high, s_scalar, 31+128); + // Regular double & add for the rest + for (int i = 30; i >= 0; i--) { + ge_double(p, p, &tmp_d); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_low , s_scalar, i); + lookup_add(p, &tmp_c, tmp_a, tmp_b, b_comb_high, s_scalar, i+128); + } + // Note: we could save one addition at the end if we assumed the + // scalar fit in 252 bit. Which it does in practice if it is + // selected at random. However, non-random, non-hashed scalars + // *can* overflow 252 bits in practice. Better account for that + // than leaving that kind of subtle corner case. + + WIPE_BUFFER(tmp_a); WIPE_CTX(&tmp_d); + WIPE_BUFFER(tmp_b); WIPE_CTX(&tmp_c); + WIPE_BUFFER(s_scalar); +} + +void crypto_sign_public_key_custom_hash(u8 public_key[32], + const u8 secret_key[32], + const crypto_sign_vtable *hash) +{ + u8 a[64]; + hash->hash(a, secret_key, 32); + trim_scalar(a); + ge A; + ge_scalarmult_base(&A, a); + ge_tobytes(public_key, &A); + WIPE_BUFFER(a); + WIPE_CTX(&A); +} + +void crypto_sign_public_key(u8 public_key[32], const u8 secret_key[32]) +{ + crypto_sign_public_key_custom_hash(public_key, secret_key, + &crypto_blake2b_vtable); +} + +void crypto_sign_init_first_pass_custom_hash(crypto_sign_ctx_abstract *ctx, + const u8 secret_key[32], + const u8 public_key[32], + const crypto_sign_vtable *hash) +{ + ctx->hash = hash; // set vtable + u8 *a = ctx->buf; + u8 *prefix = ctx->buf + 32; + ctx->hash->hash(a, secret_key, 32); + trim_scalar(a); + + if (public_key == 0) { + crypto_sign_public_key_custom_hash(ctx->pk, secret_key, ctx->hash); + } else { + COPY(ctx->pk, public_key, 32); + } + + // Deterministic part of EdDSA: Construct a nonce by hashing the message + // instead of generating a random number. + // An actual random number would work just fine, and would save us + // the trouble of hashing the message twice. If we did that + // however, the user could fuck it up and reuse the nonce. + ctx->hash->init (ctx); + ctx->hash->update(ctx, prefix , 32); +} + +void crypto_sign_init_first_pass(crypto_sign_ctx_abstract *ctx, + const u8 secret_key[32], + const u8 public_key[32]) +{ + crypto_sign_init_first_pass_custom_hash(ctx, secret_key, public_key, + &crypto_blake2b_vtable); +} + +void crypto_sign_update(crypto_sign_ctx_abstract *ctx, + const u8 *msg, size_t msg_size) +{ + ctx->hash->update(ctx, msg, msg_size); +} + +void crypto_sign_init_second_pass(crypto_sign_ctx_abstract *ctx) +{ + u8 *r = ctx->buf + 32; + u8 *half_sig = ctx->buf + 64; + ctx->hash->final(ctx, r); + reduce(r); + + // first half of the signature = "random" nonce times the base point + ge R; + ge_scalarmult_base(&R, r); + ge_tobytes(half_sig, &R); + WIPE_CTX(&R); + + // Hash R, the public key, and the message together. + // It cannot be done in parallel with the first hash. + ctx->hash->init (ctx); + ctx->hash->update(ctx, half_sig, 32); + ctx->hash->update(ctx, ctx->pk , 32); +} + +void crypto_sign_final(crypto_sign_ctx_abstract *ctx, u8 signature[64]) +{ + u8 *a = ctx->buf; + u8 *r = ctx->buf + 32; + u8 *half_sig = ctx->buf + 64; + u8 h_ram[64]; + ctx->hash->final(ctx, h_ram); + reduce(h_ram); + COPY(signature, half_sig, 32); + mul_add(signature + 32, h_ram, a, r); // s = h_ram * a + r + WIPE_BUFFER(h_ram); + crypto_wipe(ctx, ctx->hash->ctx_size); +} + +void crypto_sign(u8 signature[64], + const u8 secret_key[32], + const u8 public_key[32], + const u8 *message, size_t message_size) +{ + crypto_sign_ctx ctx; + crypto_sign_ctx_abstract *actx = (crypto_sign_ctx_abstract*)&ctx; + crypto_sign_init_first_pass (actx, secret_key, public_key); + crypto_sign_update (actx, message, message_size); + crypto_sign_init_second_pass(actx); + crypto_sign_update (actx, message, message_size); + crypto_sign_final (actx, signature); +} + +void crypto_check_init_custom_hash(crypto_check_ctx_abstract *ctx, + const u8 signature[64], + const u8 public_key[32], + const crypto_sign_vtable *hash) +{ + ctx->hash = hash; // set vtable + COPY(ctx->buf, signature , 64); + COPY(ctx->pk , public_key, 32); + ctx->hash->init (ctx); + ctx->hash->update(ctx, signature , 32); + ctx->hash->update(ctx, public_key, 32); +} + +void crypto_check_init(crypto_check_ctx_abstract *ctx, const u8 signature[64], + const u8 public_key[32]) +{ + crypto_check_init_custom_hash(ctx, signature, public_key, + &crypto_blake2b_vtable); +} + +void crypto_check_update(crypto_check_ctx_abstract *ctx, + const u8 *msg, size_t msg_size) +{ + ctx->hash->update(ctx, msg, msg_size); +} + +int crypto_check_final(crypto_check_ctx_abstract *ctx) +{ + u8 h_ram[64]; + ctx->hash->final(ctx, h_ram); + reduce(h_ram); + u8 *R = ctx->buf; // R + u8 *s = ctx->buf + 32; // s + u8 *R_check = ctx->pk; // overwrite ctx->pk to save stack space + if (ge_r_check(R_check, s, h_ram, ctx->pk)) { + return -1; + } + return crypto_verify32(R, R_check); // R == R_check ? OK : fail +} + +int crypto_check(const u8 signature[64], const u8 public_key[32], + const u8 *message, size_t message_size) +{ + crypto_check_ctx ctx; + crypto_check_ctx_abstract *actx = (crypto_check_ctx_abstract*)&ctx; + crypto_check_init (actx, signature, public_key); + crypto_check_update(actx, message, message_size); + return crypto_check_final(actx); +} + +/////////////////////// +/// EdDSA to X25519 /// +/////////////////////// +void crypto_from_eddsa_private(u8 x25519[32], const u8 eddsa[32]) +{ + u8 a[64]; + crypto_blake2b(a, eddsa, 32); + COPY(x25519, a, 32); + WIPE_BUFFER(a); +} + +void crypto_from_eddsa_public(u8 x25519[32], const u8 eddsa[32]) +{ + fe t1, t2; + fe_frombytes(t2, eddsa); + fe_add(t1, fe_one, t2); + fe_sub(t2, fe_one, t2); + fe_invert(t2, t2); + fe_mul(t1, t1, t2); + fe_tobytes(x25519, t1); + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); +} + +///////////////////////////////////////////// +/// Dirty ephemeral public key generation /// +///////////////////////////////////////////// + +// Those functions generates a public key, *without* clearing the +// cofactor. Sending that key over the network leaks 3 bits of the +// private key. Use only to generate ephemeral keys that will be hidden +// with crypto_curve_to_hidden(). +// +// The public key is otherwise compatible with crypto_x25519() and +// crypto_key_exchange() (those properly clear the cofactor). +// +// Note that the distribution of the resulting public keys is almost +// uniform. Flipping the sign of the v coordinate (not provided by this +// function), covers the entire key space almost perfectly, where +// "almost" means a 2^-128 bias (undetectable). This uniformity is +// needed to ensure the proper randomness of the resulting +// representatives (once we apply crypto_curve_to_hidden()). +// +// Recall that Curve25519 has order C = 2^255 + e, with e < 2^128 (not +// to be confused with the prime order of the main subgroup, L, which is +// 8 times less than that). +// +// Generating all points would require us to multiply a point of order C +// (the base point plus any point of order 8) by all scalars from 0 to +// C-1. Clamping limits us to scalars between 2^254 and 2^255 - 1. But +// by negating the resulting point at random, we also cover scalars from +// -2^255 + 1 to -2^254 (which modulo C is congruent to e+1 to 2^254 + e). +// +// In practice: +// - Scalars from 0 to e + 1 are never generated +// - Scalars from 2^255 to 2^255 + e are never generated +// - Scalars from 2^254 + 1 to 2^254 + e are generated twice +// +// Since e < 2^128, detecting this bias requires observing over 2^100 +// representatives from a given source (this will never happen), *and* +// recovering enough of the private key to determine that they do, or do +// not, belong to the biased set (this practically requires solving +// discrete logarithm, which is conjecturally intractable). +// +// In practice, this means the bias is impossible to detect. + +// s + (x*L) % 8*L +// Guaranteed to fit in 256 bits iff s fits in 255 bits. +// L < 2^253 +// x%8 < 2^3 +// L * (x%8) < 2^255 +// s < 2^255 +// s + L * (x%8) < 2^256 +static void add_xl(u8 s[32], u8 x) +{ + u64 mod8 = x & 7; + u64 carry = 0; + FOR (i , 0, 8) { + carry = carry + load32_le(s + 4*i) + L[i] * mod8; + store32_le(s + 4*i, (u32)carry); + carry >>= 32; + } +} + +// "Small" dirty ephemeral key. +// Use if you need to shrink the size of the binary, and can afford to +// slow down by a factor of two (compared to the fast version) +// +// This version works by decoupling the cofactor from the main factor. +// +// - The trimmed scalar determines the main factor +// - The clamped bits of the scalar determine the cofactor. +// +// Cofactor and main factor are combined into a single scalar, which is +// then multiplied by a point of order 8*L (unlike the base point, which +// has prime order). That "dirty" base point is the addition of the +// regular base point (9), and a point of order 8. +void crypto_x25519_dirty_small(u8 public_key[32], const u8 secret_key[32]) +{ + // Base point of order 8*L + // Raw scalar multiplication with it does not clear the cofactor, + // and the resulting public key will reveal 3 bits of the scalar. + static const u8 dirty_base_point[32] = { + 0x34, 0xfc, 0x6c, 0xb7, 0xc8, 0xde, 0x58, 0x97, 0x77, 0x70, 0xd9, 0x52, + 0x16, 0xcc, 0xdc, 0x6c, 0x85, 0x90, 0xbe, 0xcd, 0x91, 0x9c, 0x07, 0x59, + 0x94, 0x14, 0x56, 0x3b, 0x4b, 0xa4, 0x47, 0x0f, }; + // separate the main factor & the cofactor of the scalar + u8 scalar[32]; + COPY(scalar, secret_key, 32); + trim_scalar(scalar); + + // Separate the main factor and the cofactor + // + // The scalar is trimmed, so its cofactor is cleared. The three + // least significant bits however still have a main factor. We must + // remove it for X25519 compatibility. + // + // We exploit the fact that 5*L = 1 (modulo 8) + // cofactor = lsb * 5 * L (modulo 8*L) + // combined = scalar + cofactor (modulo 8*L) + // combined = scalar + (lsb * 5 * L) (modulo 8*L) + add_xl(scalar, secret_key[0] * 5); + scalarmult(public_key, scalar, dirty_base_point, 256); + WIPE_BUFFER(scalar); +} + +// "Fast" dirty ephemeral key +// We use this one by default. +// +// This version works by performing a regular scalar multiplication, +// then add a low order point. The scalar multiplication is done in +// Edwards space for more speed (*2 compared to the "small" version). +// The cost is a bigger binary for programs that don't also sign messages. +void crypto_x25519_dirty_fast(u8 public_key[32], const u8 secret_key[32]) +{ + u8 scalar[32]; + ge pk; + COPY(scalar, secret_key, 32); + trim_scalar(scalar); + ge_scalarmult_base(&pk, scalar); + + // Select low order point + // We're computing the [cofactor]lop scalar multiplication, where: + // cofactor = tweak & 7. + // lop = (lop_x, lop_y) + // lop_x = sqrt((sqrt(d + 1) + 1) / d) + // lop_y = -lop_x * sqrtm1 + // Notes: + // - A (single) Montgomery ladder would be twice as slow. + // - An actual scalar multiplication would hurt performance. + // - A full table lookup would take more code. + u8 cofactor = secret_key[0] & 7; + int a = (cofactor >> 2) & 1; + int b = (cofactor >> 1) & 1; + int c = (cofactor >> 0) & 1; + fe t1, t2, t3; + fe_0(t1); + fe_ccopy(t1, sqrtm1, b); + fe_ccopy(t1, lop_x , c); + fe_neg (t3, t1); + fe_ccopy(t1, t3, a); + fe_1(t2); + fe_0(t3); + fe_ccopy(t2, t3 , b); + fe_ccopy(t2, lop_y, c); + fe_neg (t3, t2); + fe_ccopy(t2, t3, a^b); + ge_precomp low_order_point; + fe_add(low_order_point.Yp, t2, t1); + fe_sub(low_order_point.Ym, t2, t1); + fe_mul(low_order_point.T2, t2, t1); + fe_mul(low_order_point.T2, low_order_point.T2, D2); + + // Add low order point to the public key + ge_madd(&pk, &pk, &low_order_point, t1, t2); + + // Convert to Montgomery u coordinate (we ignore the sign) + fe_add(t1, pk.Z, pk.Y); + fe_sub(t2, pk.Z, pk.Y); + fe_invert(t2, t2); + fe_mul(t1, t1, t2); + + fe_tobytes(public_key, t1); + + WIPE_BUFFER(t1); WIPE_BUFFER(scalar); + WIPE_BUFFER(t2); WIPE_CTX(&pk); + WIPE_BUFFER(t3); WIPE_CTX(&low_order_point); +} + +/////////////////// +/// Elligator 2 /// +/////////////////// +static const fe A = {486662}; + +// Elligator direct map +// +// Computes the point corresponding to a representative, encoded in 32 +// bytes (little Endian). Since positive representatives fits in 254 +// bits, The two most significant bits are ignored. +// +// From the paper: +// w = -A / (fe(1) + non_square * r^2) +// e = chi(w^3 + A*w^2 + w) +// u = e*w - (fe(1)-e)*(A//2) +// v = -e * sqrt(u^3 + A*u^2 + u) +// +// We ignore v because we don't need it for X25519 (the Montgomery +// ladder only uses u). +// +// Note that e is either 0, 1 or -1 +// if e = 0 u = 0 and v = 0 +// if e = 1 u = w +// if e = -1 u = -w - A = w * non_square * r^2 +// +// Let r1 = non_square * r^2 +// Let r2 = 1 + r1 +// Note that r2 cannot be zero, -1/non_square is not a square. +// We can (tediously) verify that: +// w^3 + A*w^2 + w = (A^2*r1 - r2^2) * A / r2^3 +// Therefore: +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) * 1 +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3)) * chi(r2^6) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * (A / r2^3) * r2^6) +// chi(w^3 + A*w^2 + w) = chi((A^2*r1 - r2^2) * A * r2^3) +// Corollary: +// e = 1 if (A^2*r1 - r2^2) * A * r2^3) is a non-zero square +// e = -1 if (A^2*r1 - r2^2) * A * r2^3) is not a square +// Note that w^3 + A*w^2 + w (and therefore e) can never be zero: +// w^3 + A*w^2 + w = w * (w^2 + A*w + 1) +// w^3 + A*w^2 + w = w * (w^2 + A*w + A^2/4 - A^2/4 + 1) +// w^3 + A*w^2 + w = w * (w + A/2)^2 - A^2/4 + 1) +// which is zero only if: +// w = 0 (impossible) +// (w + A/2)^2 = A^2/4 - 1 (impossible, because A^2/4-1 is not a square) +// +// Let isr = invsqrt((A^2*r1 - r2^2) * A * r2^3) +// isr = sqrt(1 / ((A^2*r1 - r2^2) * A * r2^3)) if e = 1 +// isr = sqrt(sqrt(-1) / ((A^2*r1 - r2^2) * A * r2^3)) if e = -1 +// +// if e = 1 +// let u1 = -A * (A^2*r1 - r2^2) * A * r2^2 * isr^2 +// u1 = w +// u1 = u +// +// if e = -1 +// let ufactor = -non_square * sqrt(-1) * r^2 +// let vfactor = sqrt(ufactor) +// let u2 = -A * (A^2*r1 - r2^2) * A * r2^2 * isr^2 * ufactor +// u2 = w * -1 * -non_square * r^2 +// u2 = w * non_square * r^2 +// u2 = u +void crypto_hidden_to_curve(uint8_t curve[32], const uint8_t hidden[32]) +{ + // Representatives are encoded in 254 bits. + // The two most significant ones are random padding that must be ignored. + u8 clamped[32]; + COPY(clamped, hidden, 32); + clamped[31] &= 0x3f; + + fe r, u, t1, t2, t3; + fe_frombytes(r, clamped); + fe_sq2(t1, r); + fe_add(u, t1, fe_one); + fe_sq (t2, u); + fe_mul(t3, A2, t1); + fe_sub(t3, t3, t2); + fe_mul(t3, t3, A); + fe_mul(t1, t2, u); + fe_mul(t1, t3, t1); + int is_square = invsqrt(t1, t1); + fe_sq(u, r); + fe_mul(u, u, ufactor); + fe_ccopy(u, fe_one, is_square); + fe_sq (t1, t1); + fe_mul(u, u, A); + fe_mul(u, u, t3); + fe_mul(u, u, t2); + fe_mul(u, u, t1); + fe_neg(u, u); + fe_tobytes(curve, u); + + WIPE_BUFFER(t1); WIPE_BUFFER(r); + WIPE_BUFFER(t2); WIPE_BUFFER(u); + WIPE_BUFFER(t3); WIPE_BUFFER(clamped); +} + +// Elligator inverse map +// +// Computes the representative of a point, if possible. If not, it does +// nothing and returns -1. Note that the success of the operation +// depends only on the point (more precisely its u coordinate). The +// tweak parameter is used only upon success +// +// The tweak should be a random byte. Beyond that, its contents are an +// implementation detail. Currently, the tweak comprises: +// - Bit 1 : sign of the v coordinate (0 if positive, 1 if negative) +// - Bit 2-5: not used +// - Bits 6-7: random padding +// +// From the paper: +// Let sq = -non_square * u * (u+A) +// if sq is not a square, or u = -A, there is no mapping +// Assuming there is a mapping: +// if v is positive: r = sqrt(-(u+A) / u) +// if v is negative: r = sqrt(-u / (u+A)) +// +// We compute isr = invsqrt(-non_square * u * (u+A)) +// if it wasn't a non-zero square, abort. +// else, isr = sqrt(-1 / (non_square * u * (u+A)) +// +// This causes us to abort if u is zero, even though we shouldn't. This +// never happens in practice, because (i) a random point in the curve has +// a negligible chance of being zero, and (ii) scalar multiplication with +// a trimmed scalar *never* yields zero. +// +// Since: +// isr * (u+A) = sqrt(-1 / (non_square * u * (u+A)) * (u+A) +// isr * (u+A) = sqrt(-(u+A) / (non_square * u * (u+A)) +// and: +// isr = u = sqrt(-1 / (non_square * u * (u+A)) * u +// isr = u = sqrt(-u / (non_square * u * (u+A)) +// Therefore: +// if v is positive: r = isr * (u+A) +// if v is negative: r = isr * u +int crypto_curve_to_hidden(u8 hidden[32], const u8 public_key[32], u8 tweak) +{ + fe t1, t2, t3; + fe_frombytes(t1, public_key); + + fe_add(t2, t1, A); + fe_mul(t3, t1, t2); + fe_mul_small(t3, t3, -2); + int is_square = invsqrt(t3, t3); + if (!is_square) { + // The only variable time bit. This ultimately reveals how many + // tries it took us to find a representable key. + // This does not affect security as long as we try keys at random. + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); + WIPE_BUFFER(t3); + return -1; + } + fe_ccopy (t1, t2, tweak & 1); + fe_mul (t3, t1, t3); + fe_mul_small(t1, t3, 2); + fe_neg (t2, t3); + fe_ccopy (t3, t2, fe_isodd(t1)); + fe_tobytes(hidden, t3); + + // Pad with two random bits + hidden[31] |= tweak & 0xc0; + + WIPE_BUFFER(t1); + WIPE_BUFFER(t2); + WIPE_BUFFER(t3); + return 0; +} + +void crypto_hidden_key_pair(u8 hidden[32], u8 secret_key[32], u8 seed[32]) +{ + u8 pk [32]; // public key + u8 buf[64]; // seed + representative + COPY(buf + 32, seed, 32); + do { + crypto_chacha20(buf, 0, 64, buf+32, zero); + crypto_x25519_dirty_fast(pk, buf); // or the "small" version + } while(crypto_curve_to_hidden(buf+32, pk, buf[32])); + // Note that the return value of crypto_curve_to_hidden() is + // independent from its tweak parameter. + // Therefore, buf[32] is not actually reused. Either we loop one + // more time and buf[32] is used for the new seed, or we succeeded, + // and buf[32] becomes the tweak parameter. + + crypto_wipe(seed, 32); + COPY(hidden , buf + 32, 32); + COPY(secret_key, buf , 32); + WIPE_BUFFER(buf); + WIPE_BUFFER(pk); +} + +//////////////////// +/// Key exchange /// +//////////////////// +void crypto_key_exchange(u8 shared_key[32], + const u8 your_secret_key [32], + const u8 their_public_key[32]) +{ + crypto_x25519(shared_key, your_secret_key, their_public_key); + crypto_hchacha20(shared_key, shared_key, zero); +} + +/////////////////////// +/// Scalar division /// +/////////////////////// + +// Montgomery reduction. +// Divides x by (2^256), and reduces the result modulo L +// +// Precondition: +// x < L * 2^256 +// Constants: +// r = 2^256 (makes division by r trivial) +// k = (r * (1/r) - 1) // L (1/r is computed modulo L ) +// Algorithm: +// s = (x * k) % r +// t = x + s*L (t is always a multiple of r) +// u = (t/r) % L (u is always below 2*L, conditional subtraction is enough) +static void redc(u32 u[8], u32 x[16]) +{ + static const u32 k[8] = { 0x12547e1b, 0xd2b51da3, 0xfdba84ff, 0xb1a206f2, + 0xffa36bea, 0x14e75438, 0x6fe91836, 0x9db6c6f2,}; + static const u32 l[8] = { 0x5cf5d3ed, 0x5812631a, 0xa2f79cd6, 0x14def9de, + 0x00000000, 0x00000000, 0x00000000, 0x10000000,}; + // s = x * k (modulo 2^256) + // This is cheaper than the full multiplication. + u32 s[8] = {0}; + FOR (i, 0, 8) { + u64 carry = 0; + FOR (j, 0, 8-i) { + carry += s[i+j] + (u64)x[i] * k[j]; + s[i+j] = (u32)carry; + carry >>= 32; + } + } + u32 t[16] = {0}; + multiply(t, s, l); + + // t = t + x + u64 carry = 0; + FOR (i, 0, 16) { + carry += (u64)t[i] + x[i]; + t[i] = (u32)carry; + carry >>= 32; + } + + // u = (t / 2^256) % L + // Note that t / 2^256 is always below 2*L, + // So a constant time conditional subtraction is enough + // We work with L directly, in a 2's complement encoding + // (-L == ~L + 1) + remove_l(u, t+8); + + WIPE_BUFFER(s); + WIPE_BUFFER(t); +} + +void crypto_x25519_inverse(u8 blind_salt [32], const u8 private_key[32], + const u8 curve_point[32]) +{ + static const u8 Lm2[32] = { // L - 2 + 0xeb, 0xd3, 0xf5, 0x5c, 0x1a, 0x63, 0x12, 0x58, 0xd6, 0x9c, 0xf7, 0xa2, + 0xde, 0xf9, 0xde, 0x14, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x10, }; + // 1 in Montgomery form + u32 m_inv [8] = {0x8d98951d, 0xd6ec3174, 0x737dcf70, 0xc6ef5bf4, + 0xfffffffe, 0xffffffff, 0xffffffff, 0x0fffffff,}; + + u8 scalar[32]; + COPY(scalar, private_key, 32); + trim_scalar(scalar); + + // Convert the scalar in Montgomery form + // m_scl = scalar * 2^256 (modulo L) + u32 m_scl[8]; + { + u32 tmp[16]; + ZERO(tmp, 8); + load32_le_buf(tmp+8, scalar, 8); + mod_l(scalar, tmp); + load32_le_buf(m_scl, scalar, 8); + WIPE_BUFFER(tmp); // Wipe ASAP to save stack space + } + + u32 product[16]; + for (int i = 252; i >= 0; i--) { + ZERO(product, 16); + multiply(product, m_inv, m_inv); + redc(m_inv, product); + if (scalar_bit(Lm2, i)) { + ZERO(product, 16); + multiply(product, m_inv, m_scl); + redc(m_inv, product); + } + } + // Convert the inverse *out* of Montgomery form + // scalar = m_inv / 2^256 (modulo L) + COPY(product, m_inv, 8); + ZERO(product + 8, 8); + redc(m_inv, product); + store32_le_buf(scalar, m_inv, 8); // the *inverse* of the scalar + + // Clear the cofactor of scalar: + // cleared = scalar * (3*L + 1) (modulo 8*L) + // cleared = scalar + scalar * 3 * L (modulo 8*L) + // Note that (scalar * 3) is reduced modulo 8, so we only need the + // first byte. + add_xl(scalar, scalar[0] * 3); + + // Recall that 8*L < 2^256. However it is also very close to + // 2^255. If we spanned the ladder over 255 bits, random tests + // wouldn't catch the off-by-one error. + scalarmult(blind_salt, scalar, curve_point, 256); + + WIPE_BUFFER(scalar); WIPE_BUFFER(m_scl); + WIPE_BUFFER(product); WIPE_BUFFER(m_inv); +} + +//////////////////////////////// +/// Authenticated encryption /// +//////////////////////////////// +static void lock_auth(u8 mac[16], const u8 auth_key[32], + const u8 *ad , size_t ad_size, + const u8 *cipher_text, size_t text_size) +{ + u8 sizes[16]; // Not secret, not wiped + store64_le(sizes + 0, ad_size); + store64_le(sizes + 8, text_size); + crypto_poly1305_ctx poly_ctx; // auto wiped... + crypto_poly1305_init (&poly_ctx, auth_key); + crypto_poly1305_update(&poly_ctx, ad , ad_size); + crypto_poly1305_update(&poly_ctx, zero , align(ad_size, 16)); + crypto_poly1305_update(&poly_ctx, cipher_text, text_size); + crypto_poly1305_update(&poly_ctx, zero , align(text_size, 16)); + crypto_poly1305_update(&poly_ctx, sizes , 16); + crypto_poly1305_final (&poly_ctx, mac); // ...here +} + +void crypto_lock_aead(u8 mac[16], u8 *cipher_text, + const u8 key[32], const u8 nonce[24], + const u8 *ad , size_t ad_size, + const u8 *plain_text, size_t text_size) +{ + u8 sub_key[32]; + u8 auth_key[64]; // "Wasting" the whole Chacha block is faster + crypto_hchacha20(sub_key, key, nonce); + crypto_chacha20(auth_key, 0, 64, sub_key, nonce + 16); + crypto_chacha20_ctr(cipher_text, plain_text, text_size, + sub_key, nonce + 16, 1); + lock_auth(mac, auth_key, ad, ad_size, cipher_text, text_size); + WIPE_BUFFER(sub_key); + WIPE_BUFFER(auth_key); +} + +int crypto_unlock_aead(u8 *plain_text, const u8 key[32], const u8 nonce[24], + const u8 mac[16], + const u8 *ad , size_t ad_size, + const u8 *cipher_text, size_t text_size) +{ + u8 sub_key[32]; + u8 auth_key[64]; // "Wasting" the whole Chacha block is faster + crypto_hchacha20(sub_key, key, nonce); + crypto_chacha20(auth_key, 0, 64, sub_key, nonce + 16); + u8 real_mac[16]; + lock_auth(real_mac, auth_key, ad, ad_size, cipher_text, text_size); + WIPE_BUFFER(auth_key); + if (crypto_verify16(mac, real_mac)) { + WIPE_BUFFER(sub_key); + WIPE_BUFFER(real_mac); + return -1; + } + crypto_chacha20_ctr(plain_text, cipher_text, text_size, + sub_key, nonce + 16, 1); + WIPE_BUFFER(sub_key); + WIPE_BUFFER(real_mac); + return 0; +} + +void crypto_lock(u8 mac[16], u8 *cipher_text, + const u8 key[32], const u8 nonce[24], + const u8 *plain_text, size_t text_size) +{ + crypto_lock_aead(mac, cipher_text, key, nonce, 0, 0, plain_text, text_size); +} + +int crypto_unlock(u8 *plain_text, + const u8 key[32], const u8 nonce[24], const u8 mac[16], + const u8 *cipher_text, size_t text_size) +{ + return crypto_unlock_aead(plain_text, key, nonce, mac, 0, 0, + cipher_text, text_size); +} diff --git a/RemoteIDModule/monocypher.h b/RemoteIDModule/monocypher.h new file mode 100644 index 0000000..304aabb --- /dev/null +++ b/RemoteIDModule/monocypher.h @@ -0,0 +1,374 @@ +// Monocypher version 3.1.2 +// +// This file is dual-licensed. Choose whichever licence you want from +// the two licences listed below. +// +// The first licence is a regular 2-clause BSD licence. The second licence +// is the CC-0 from Creative Commons. It is intended to release Monocypher +// to the public domain. The BSD licence serves as a fallback option. +// +// SPDX-License-Identifier: BSD-2-Clause OR CC0-1.0 +// +// ------------------------------------------------------------------------ +// +// Copyright (c) 2017-2019, Loup Vaillant +// All rights reserved. +// +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// 1. Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// 2. Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the +// distribution. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +// +// ------------------------------------------------------------------------ +// +// Written in 2017-2019 by Loup Vaillant +// +// To the extent possible under law, the author(s) have dedicated all copyright +// and related neighboring rights to this software to the public domain +// worldwide. This software is distributed without any warranty. +// +// You should have received a copy of the CC0 Public Domain Dedication along +// with this software. If not, see +// + +#ifndef MONOCYPHER_H +#define MONOCYPHER_H + +#include +#include + +//////////////////////// +/// Type definitions /// +//////////////////////// + +// Vtable for EdDSA with a custom hash. +// Instantiate it to define a custom hash. +// Its size, contents, and layout, are part of the public API. +typedef struct { + void (*hash)(uint8_t hash[64], const uint8_t *message, size_t message_size); + void (*init )(void *ctx); + void (*update)(void *ctx, const uint8_t *message, size_t message_size); + void (*final )(void *ctx, uint8_t hash[64]); + size_t ctx_size; +} crypto_sign_vtable; + +// Do not rely on the size or contents of any of the types below, +// they may change without notice. + +// Poly1305 +typedef struct { + uint32_t r[4]; // constant multiplier (from the secret key) + uint32_t h[5]; // accumulated hash + uint32_t c[5]; // chunk of the message + uint32_t pad[4]; // random number added at the end (from the secret key) + size_t c_idx; // How many bytes are there in the chunk. +} crypto_poly1305_ctx; + +// Hash (Blake2b) +typedef struct { + uint64_t hash[8]; + uint64_t input_offset[2]; + uint64_t input[16]; + size_t input_idx; + size_t hash_size; +} crypto_blake2b_ctx; + +// Signatures (EdDSA) +typedef struct { + const crypto_sign_vtable *hash; + uint8_t buf[96]; + uint8_t pk [32]; +} crypto_sign_ctx_abstract; +typedef crypto_sign_ctx_abstract crypto_check_ctx_abstract; + +typedef struct { + crypto_sign_ctx_abstract ctx; + crypto_blake2b_ctx hash; +} crypto_sign_ctx; +typedef crypto_sign_ctx crypto_check_ctx; + +//////////////////////////// +/// High level interface /// +//////////////////////////// + +// Constant time comparisons +// ------------------------- + +// Return 0 if a and b are equal, -1 otherwise +int crypto_verify16(const uint8_t a[16], const uint8_t b[16]); +int crypto_verify32(const uint8_t a[32], const uint8_t b[32]); +int crypto_verify64(const uint8_t a[64], const uint8_t b[64]); + +// Erase sensitive data +// -------------------- + +// Please erase all copies +void crypto_wipe(void *secret, size_t size); + + +// Authenticated encryption +// ------------------------ +void crypto_lock(uint8_t mac[16], + uint8_t *cipher_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t *plain_text, size_t text_size); +int crypto_unlock(uint8_t *plain_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t mac[16], + const uint8_t *cipher_text, size_t text_size); + +// With additional data +void crypto_lock_aead(uint8_t mac[16], + uint8_t *cipher_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t *ad , size_t ad_size, + const uint8_t *plain_text, size_t text_size); +int crypto_unlock_aead(uint8_t *plain_text, + const uint8_t key[32], + const uint8_t nonce[24], + const uint8_t mac[16], + const uint8_t *ad , size_t ad_size, + const uint8_t *cipher_text, size_t text_size); + + +// General purpose hash (Blake2b) +// ------------------------------ + +// Direct interface +void crypto_blake2b(uint8_t hash[64], + const uint8_t *message, size_t message_size); + +void crypto_blake2b_general(uint8_t *hash , size_t hash_size, + const uint8_t *key , size_t key_size, // optional + const uint8_t *message, size_t message_size); + +// Incremental interface +void crypto_blake2b_init (crypto_blake2b_ctx *ctx); +void crypto_blake2b_update(crypto_blake2b_ctx *ctx, + const uint8_t *message, size_t message_size); +void crypto_blake2b_final (crypto_blake2b_ctx *ctx, uint8_t *hash); + +void crypto_blake2b_general_init(crypto_blake2b_ctx *ctx, size_t hash_size, + const uint8_t *key, size_t key_size); + +// vtable for signatures +extern const crypto_sign_vtable crypto_blake2b_vtable; + + +// Password key derivation (Argon2 i) +// ---------------------------------- +void crypto_argon2i(uint8_t *hash, uint32_t hash_size, // >= 4 + void *work_area, uint32_t nb_blocks, // >= 8 + uint32_t nb_iterations, // >= 3 + const uint8_t *password, uint32_t password_size, + const uint8_t *salt, uint32_t salt_size); // >= 8 + +void crypto_argon2i_general(uint8_t *hash, uint32_t hash_size,// >= 4 + void *work_area, uint32_t nb_blocks,// >= 8 + uint32_t nb_iterations, // >= 3 + const uint8_t *password, uint32_t password_size, + const uint8_t *salt, uint32_t salt_size,// >= 8 + const uint8_t *key, uint32_t key_size, + const uint8_t *ad, uint32_t ad_size); + + +// Key exchange (x25519 + HChacha20) +// --------------------------------- +#define crypto_key_exchange_public_key crypto_x25519_public_key +void crypto_key_exchange(uint8_t shared_key [32], + const uint8_t your_secret_key [32], + const uint8_t their_public_key[32]); + + +// Signatures (EdDSA with curve25519 + Blake2b) +// -------------------------------------------- + +// Generate public key +void crypto_sign_public_key(uint8_t public_key[32], + const uint8_t secret_key[32]); + +// Direct interface +void crypto_sign(uint8_t signature [64], + const uint8_t secret_key[32], + const uint8_t public_key[32], // optional, may be 0 + const uint8_t *message, size_t message_size); +int crypto_check(const uint8_t signature [64], + const uint8_t public_key[32], + const uint8_t *message, size_t message_size); + +//////////////////////////// +/// Low level primitives /// +//////////////////////////// + +// For experts only. You have been warned. + +// Chacha20 +// -------- + +// Specialised hash. +// Used to hash X25519 shared secrets. +void crypto_hchacha20(uint8_t out[32], + const uint8_t key[32], + const uint8_t in [16]); + +// Unauthenticated stream cipher. +// Don't forget to add authentication. +void crypto_chacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[8]); +void crypto_xchacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[24]); +void crypto_ietf_chacha20(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[12]); +uint64_t crypto_chacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[8], + uint64_t ctr); +uint64_t crypto_xchacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[24], + uint64_t ctr); +uint32_t crypto_ietf_chacha20_ctr(uint8_t *cipher_text, + const uint8_t *plain_text, + size_t text_size, + const uint8_t key[32], + const uint8_t nonce[12], + uint32_t ctr); + +// Poly 1305 +// --------- + +// This is a *one time* authenticator. +// Disclosing the mac reveals the key. +// See crypto_lock() on how to use it properly. + +// Direct interface +void crypto_poly1305(uint8_t mac[16], + const uint8_t *message, size_t message_size, + const uint8_t key[32]); + +// Incremental interface +void crypto_poly1305_init (crypto_poly1305_ctx *ctx, const uint8_t key[32]); +void crypto_poly1305_update(crypto_poly1305_ctx *ctx, + const uint8_t *message, size_t message_size); +void crypto_poly1305_final (crypto_poly1305_ctx *ctx, uint8_t mac[16]); + + +// X-25519 +// ------- + +// Shared secrets are not quite random. +// Hash them to derive an actual shared key. +void crypto_x25519_public_key(uint8_t public_key[32], + const uint8_t secret_key[32]); +void crypto_x25519(uint8_t raw_shared_secret[32], + const uint8_t your_secret_key [32], + const uint8_t their_public_key [32]); + +// "Dirty" versions of x25519_public_key() +// Only use to generate ephemeral keys you want to hide. +// Note that those functions leaks 3 bits of the private key. +void crypto_x25519_dirty_small(uint8_t pk[32], const uint8_t sk[32]); +void crypto_x25519_dirty_fast (uint8_t pk[32], const uint8_t sk[32]); + +// scalar "division" +// Used for OPRF. Be aware that exponential blinding is less secure +// than Diffie-Hellman key exchange. +void crypto_x25519_inverse(uint8_t blind_salt [32], + const uint8_t private_key[32], + const uint8_t curve_point[32]); + + +// EdDSA to X25519 +// --------------- +void crypto_from_eddsa_private(uint8_t x25519[32], const uint8_t eddsa[32]); +void crypto_from_eddsa_public (uint8_t x25519[32], const uint8_t eddsa[32]); + + +// EdDSA -- Incremental interface +// ------------------------------ + +// Signing (2 passes) +// Make sure the two passes hash the same message, +// else you might reveal the private key. +void crypto_sign_init_first_pass(crypto_sign_ctx_abstract *ctx, + const uint8_t secret_key[32], + const uint8_t public_key[32]); +void crypto_sign_update(crypto_sign_ctx_abstract *ctx, + const uint8_t *message, size_t message_size); +void crypto_sign_init_second_pass(crypto_sign_ctx_abstract *ctx); +// use crypto_sign_update() again. +void crypto_sign_final(crypto_sign_ctx_abstract *ctx, uint8_t signature[64]); + +// Verification (1 pass) +// Make sure you don't use (parts of) the message +// before you're done checking it. +void crypto_check_init (crypto_check_ctx_abstract *ctx, + const uint8_t signature[64], + const uint8_t public_key[32]); +void crypto_check_update(crypto_check_ctx_abstract *ctx, + const uint8_t *message, size_t message_size); +int crypto_check_final (crypto_check_ctx_abstract *ctx); + +// Custom hash interface +void crypto_sign_public_key_custom_hash(uint8_t public_key[32], + const uint8_t secret_key[32], + const crypto_sign_vtable *hash); +void crypto_sign_init_first_pass_custom_hash(crypto_sign_ctx_abstract *ctx, + const uint8_t secret_key[32], + const uint8_t public_key[32], + const crypto_sign_vtable *hash); +void crypto_check_init_custom_hash(crypto_check_ctx_abstract *ctx, + const uint8_t signature[64], + const uint8_t public_key[32], + const crypto_sign_vtable *hash); + +// Elligator 2 +// ----------- + +// Elligator mappings proper +void crypto_hidden_to_curve(uint8_t curve [32], const uint8_t hidden[32]); +int crypto_curve_to_hidden(uint8_t hidden[32], const uint8_t curve [32], + uint8_t tweak); + +// Easy to use key pair generation +void crypto_hidden_key_pair(uint8_t hidden[32], uint8_t secret_key[32], + uint8_t seed[32]); + + +#endif // MONOCYPHER_H diff --git a/RemoteIDModule/options.h b/RemoteIDModule/options.h index 020aa46..9e7c8a5 100644 --- a/RemoteIDModule/options.h +++ b/RemoteIDModule/options.h @@ -21,6 +21,3 @@ // do we support MAVLink connnection to flight controller? #define AP_MAVLINK_ENABLED 1 - -// define the output update rate -#define OUTPUT_RATE_HZ 1 //this is the minimum update rate according to the docs. More transmissions will increase interferency to other radio modules. diff --git a/RemoteIDModule/parameters.cpp b/RemoteIDModule/parameters.cpp new file mode 100644 index 0000000..2b6e781 --- /dev/null +++ b/RemoteIDModule/parameters.cpp @@ -0,0 +1,185 @@ +#include "options.h" +#include +#include "parameters.h" +#include +#include + +Parameters g; +static nvs_handle handle; + +const Parameters::Param Parameters::params[] = { + { "LOCK_LEVEL", Parameters::ParamType::UINT8, (const void*)&g.lock_level, 0, 0, 2 }, + { "CAN_NODE", Parameters::ParamType::UINT8, (const void*)&g.can_node, 0, 0, 127 }, + { "UAS_ID", Parameters::ParamType::CHAR20, (const void*)&g.uas_id[0], 0, 0, 0 }, + { "BAUDRATE", Parameters::ParamType::UINT32, (const void*)&g.baudrate, 57600, 9600, 921600 }, + { "WIFI_NAN_RATE", Parameters::ParamType::FLOAT, (const void*)&g.wifi_nan_rate, 0, 0, 5 }, + { "BT4_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt4_rate, 1, 0, 5 }, + { "BT5_RATE", Parameters::ParamType::FLOAT, (const void*)&g.bt5_rate, 1, 0, 5 }, + { "WEBSERVER_ENABLE", Parameters::ParamType::UINT8, (const void*)&g.webserver_enable, 1, 0, 1 }, + { "WIFI_SSID", Parameters::ParamType::CHAR20, (const void*)&g.wifi_ssid, }, + { "WIFI_PASSWORD", Parameters::ParamType::CHAR20, (const void*)&g.wifi_password, 0, 0, 0, PARAM_FLAG_HIDDEN }, + { "BCAST_POWERUP", Parameters::ParamType::UINT8, (const void*)&g.bcast_powerup, 1, 0, 1 }, + { "PUBLIC_KEY1", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[0], }, + { "PUBLIC_KEY2", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[1], }, + { "PUBLIC_KEY3", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[2], }, + { "PUBLIC_KEY4", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[3], }, + { "PUBLIC_KEY5", Parameters::ParamType::CHAR64, (const void*)&g.public_keys[4], }, + { "", Parameters::ParamType::NONE, nullptr, }, +}; + +/* + find by name + */ +const Parameters::Param *Parameters::find(const char *name) +{ + for (const auto &p : params) { + if (strcmp(name, p.name) == 0) { + return &p; + } + } + return nullptr; +} + +/* + find by index + */ +const Parameters::Param *Parameters::find_by_index(uint16_t index) +{ + if (index >= (sizeof(params)/sizeof(params[0])-1)) { + return nullptr; + } + return ¶ms[index]; +} + +void Parameters::Param::set_uint8(uint8_t v) const +{ + auto *p = (uint8_t *)ptr; + *p = v; + nvs_set_u8(handle, name, *p); +} + +void Parameters::Param::set_uint32(uint32_t v) const +{ + auto *p = (uint32_t *)ptr; + *p = v; + nvs_set_u32(handle, name, *p); +} + +void Parameters::Param::set_float(float v) const +{ + auto *p = (float *)ptr; + *p = v; + union { + float f; + uint32_t u32; + } u; + u.f = v; + nvs_set_u32(handle, name, u.u32); +} + +void Parameters::Param::set_char20(const char *v) const +{ + memset((void*)ptr, 0, 21); + strncpy((char *)ptr, v, 20); + nvs_set_str(handle, name, v); +} + +void Parameters::Param::set_char64(const char *v) const +{ + memset((void*)ptr, 0, 65); + strncpy((char *)ptr, v, 64); + nvs_set_str(handle, name, v); +} + +uint8_t Parameters::Param::get_uint8() const +{ + const auto *p = (const uint8_t *)ptr; + return *p; +} + +uint32_t Parameters::Param::get_uint32() const +{ + const auto *p = (const uint32_t *)ptr; + return *p; +} + +float Parameters::Param::get_float() const +{ + const auto *p = (const float *)ptr; + return *p; +} + +const char *Parameters::Param::get_char20() const +{ + const char *p = (const char *)ptr; + return p; +} + +const char *Parameters::Param::get_char64() const +{ + const char *p = (const char *)ptr; + return p; +} + + +/* + load defaults from parameter table + */ +void Parameters::load_defaults(void) +{ + for (const auto &p : params) { + switch (p.ptype) { + case ParamType::UINT8: + *(uint8_t *)p.ptr = uint8_t(p.default_value); + break; + case ParamType::UINT32: + *(uint32_t *)p.ptr = uint32_t(p.default_value); + break; + case ParamType::FLOAT: + *(float *)p.ptr = p.default_value; + break; + } + } +} + +void Parameters::init(void) +{ + load_defaults(); + + if (nvs_flash_init() != ESP_OK || + nvs_open("storage", NVS_READWRITE, &handle) != ESP_OK) { + Serial.printf("NVS init failed\n"); + } + // load values from NVS + for (const auto &p : params) { + switch (p.ptype) { + case ParamType::UINT8: + nvs_get_u8(handle, p.name, (uint8_t *)p.ptr); + break; + case ParamType::UINT32: + nvs_get_u32(handle, p.name, (uint32_t *)p.ptr); + break; + case ParamType::FLOAT: + nvs_get_u32(handle, p.name, (uint32_t *)p.ptr); + break; + case ParamType::CHAR20: { + size_t len = 21; + nvs_get_str(handle, p.name, (char *)p.ptr, &len); + break; + } + case ParamType::CHAR64: { + size_t len = 65; + nvs_get_str(handle, p.name, (char *)p.ptr, &len); + break; + } + } + } + + if (strlen(g.wifi_ssid) == 0) { + uint8_t mac[6] {}; + esp_read_mac(mac, ESP_MAC_WIFI_STA); + snprintf(wifi_ssid, 20, "RID_%02x%02x%02x%02x%02x%02x", + mac[0], mac[1], mac[2], mac[3], mac[4], mac[5]); + + } +} diff --git a/RemoteIDModule/parameters.h b/RemoteIDModule/parameters.h new file mode 100644 index 0000000..c50caa6 --- /dev/null +++ b/RemoteIDModule/parameters.h @@ -0,0 +1,66 @@ +#pragma once + +#include + +#define MAX_PUBLIC_KEYS 5 +#define PUBLIC_KEY_LEN 32 +#define PARAM_NAME_MAX_LEN 16 + +#define PARAM_FLAG_HIDDEN (1U<<0) + +class Parameters { +public: + uint8_t lock_level; + uint8_t can_node; + uint8_t bcast_powerup; + uint32_t baudrate = 57600; + char uas_id[21] = "ABCD123456789"; + float wifi_nan_rate; + float bt4_rate; + float bt5_rate; + uint8_t webserver_enable; + char wifi_ssid[21] = "RID_123456"; + char wifi_password[21] = "penguin1234"; + struct { + char b64_key[64]; + } public_keys[MAX_PUBLIC_KEYS]; + + enum class ParamType { + NONE=0, + UINT8=1, + UINT32=2, + FLOAT=3, + CHAR20=4, + CHAR64=5, + }; + + struct Param { + char name[PARAM_NAME_MAX_LEN+1]; + ParamType ptype; + const void *ptr; + float default_value; + float min_value; + float max_value; + uint16_t flags; + void set_float(float v) const; + void set_uint8(uint8_t v) const; + void set_uint32(uint32_t v) const; + void set_char20(const char *v) const; + void set_char64(const char *v) const; + uint8_t get_uint8() const; + uint32_t get_uint32() const; + float get_float() const; + const char *get_char20() const; + const char *get_char64() const; + }; + static const struct Param params[]; + + static const Param *find(const char *name); + static const Param *find_by_index(uint16_t idx); + + void init(void); +private: + void load_defaults(void); +}; + +extern Parameters g; diff --git a/RemoteIDModule/romfs.cpp b/RemoteIDModule/romfs.cpp new file mode 100644 index 0000000..3a14018 --- /dev/null +++ b/RemoteIDModule/romfs.cpp @@ -0,0 +1,73 @@ +#include +#include "romfs.h" +#include "romfs_files.h" +#include + +const ROMFS::embedded_file *ROMFS::find(const char *fname) +{ + for (const auto &f : files) { + if (strcmp(fname, f.filename) == 0) { + Serial.printf("ROMFS Returning '%s' size=%u len=%u\n", + fname, f.size, strlen((const char *)f.contents)); + return &f; + } + } + Serial.printf("ROMFS not found '%s'\n", fname); + return nullptr; +} + +bool ROMFS::exists(const char *fname) +{ + return find(fname) != nullptr; +} + +ROMFS_Stream *ROMFS::find_stream(const char *fname) +{ + const auto *f = find(fname); + if (!f) { + return nullptr; + } + return new ROMFS_Stream(*f); +} + +size_t ROMFS_Stream::size(void) const +{ + return f.size; +} + +const char *ROMFS_Stream::name(void) const +{ + return f.filename; +} + +int ROMFS_Stream::available(void) +{ + return f.size - offset; +} + +size_t ROMFS_Stream::read(uint8_t* buf, size_t size) +{ + const auto avail = available(); + if (size > avail) { + size = avail; + } + memcpy(buf, &f.contents[offset], size); + offset += size; + return size; +} + +int ROMFS_Stream::peek(void) +{ + if (offset >= f.size) { + return -1; + } + return f.contents[offset]; +} + +int ROMFS_Stream::read(void) +{ + if (offset >= f.size) { + return -1; + } + return f.contents[offset++]; +} diff --git a/RemoteIDModule/romfs.h b/RemoteIDModule/romfs.h new file mode 100644 index 0000000..8f993c4 --- /dev/null +++ b/RemoteIDModule/romfs.h @@ -0,0 +1,47 @@ +#pragma once + +#include + +class ROMFS_Stream; + +class ROMFS { +public: + static bool exists(const char *fname); + static ROMFS_Stream *find_stream(const char *fname); + + struct embedded_file { + const char *filename; + uint32_t size; + const uint8_t *contents; + }; + +private: + static const struct embedded_file *find(const char *fname); + static const struct embedded_file files[]; +}; + +class ROMFS_Stream : public Stream +{ +public: + ROMFS_Stream(const ROMFS::embedded_file &_f) : + f(_f) {} + + size_t write(const uint8_t *buffer, size_t size) override { return 0; } + size_t write(uint8_t data) override { return 0; } + size_t size(void) const; + const char *name(void) const; + + int available() override; + int read() override; + int peek() override; + void flush() override {} + size_t readBytes(char *buffer, size_t length) override { + return read((uint8_t*)buffer, length); + } + +private: + size_t read(uint8_t* buf, size_t size); + const ROMFS::embedded_file &f; + uint32_t offset = 0; +}; + diff --git a/RemoteIDModule/version.h b/RemoteIDModule/version.h index 49b242b..e1fe233 100644 --- a/RemoteIDModule/version.h +++ b/RemoteIDModule/version.h @@ -1,4 +1,4 @@ #define FW_VERSION_MAJOR 1 -#define FW_VERSION_MINOR 6 +#define FW_VERSION_MINOR 8 #include "git-version.h" diff --git a/RemoteIDModule/web/images/bg.jpg b/RemoteIDModule/web/images/bg.jpg new file mode 100644 index 0000000..2cc21a2 Binary files /dev/null and b/RemoteIDModule/web/images/bg.jpg differ diff --git a/RemoteIDModule/web/images/button.jpg b/RemoteIDModule/web/images/button.jpg new file mode 100644 index 0000000..81e32a2 Binary files /dev/null and b/RemoteIDModule/web/images/button.jpg differ diff --git a/RemoteIDModule/web/images/logo.jpg b/RemoteIDModule/web/images/logo.jpg new file mode 100644 index 0000000..edd3410 Binary files /dev/null and b/RemoteIDModule/web/images/logo.jpg differ diff --git a/RemoteIDModule/web/index.html b/RemoteIDModule/web/index.html new file mode 100644 index 0000000..055b61c --- /dev/null +++ b/RemoteIDModule/web/index.html @@ -0,0 +1,56 @@ + + + + + + ArduRemoteID + + + + + + +

ArduRemoteID

+ +

Status

+ +

Firmware Update

+ +
+ + +
+
upload progress: 0%
+ + + + + diff --git a/RemoteIDModule/web/js/jquery.min.js b/RemoteIDModule/web/js/jquery.min.js new file mode 100644 index 0000000..644d35e --- /dev/null +++ b/RemoteIDModule/web/js/jquery.min.js @@ -0,0 +1,4 @@ +/*! jQuery v3.2.1 | (c) JS Foundation and other contributors | jquery.org/license */ +!function(a,b){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=a.document?b(a,!0):function(a){if(!a.document)throw new Error("jQuery requires a window with a document");return b(a)}:b(a)}("undefined"!=typeof window?window:this,function(a,b){"use strict";var c=[],d=a.document,e=Object.getPrototypeOf,f=c.slice,g=c.concat,h=c.push,i=c.indexOf,j={},k=j.toString,l=j.hasOwnProperty,m=l.toString,n=m.call(Object),o={};function p(a,b){b=b||d;var c=b.createElement("script");c.text=a,b.head.appendChild(c).parentNode.removeChild(c)}var q="3.2.1",r=function(a,b){return new r.fn.init(a,b)},s=/^[\s\uFEFF\xA0]+|[\s\uFEFF\xA0]+$/g,t=/^-ms-/,u=/-([a-z])/g,v=function(a,b){return b.toUpperCase()};r.fn=r.prototype={jquery:q,constructor:r,length:0,toArray:function(){return f.call(this)},get:function(a){return null==a?f.call(this):a<0?this[a+this.length]:this[a]},pushStack:function(a){var b=r.merge(this.constructor(),a);return b.prevObject=this,b},each:function(a){return r.each(this,a)},map:function(a){return this.pushStack(r.map(this,function(b,c){return a.call(b,c,b)}))},slice:function(){return this.pushStack(f.apply(this,arguments))},first:function(){return this.eq(0)},last:function(){return this.eq(-1)},eq:function(a){var b=this.length,c=+a+(a<0?b:0);return this.pushStack(c>=0&&c0&&b-1 in a)}var x=function(a){var b,c,d,e,f,g,h,i,j,k,l,m,n,o,p,q,r,s,t,u="sizzle"+1*new Date,v=a.document,w=0,x=0,y=ha(),z=ha(),A=ha(),B=function(a,b){return a===b&&(l=!0),0},C={}.hasOwnProperty,D=[],E=D.pop,F=D.push,G=D.push,H=D.slice,I=function(a,b){for(var c=0,d=a.length;c+~]|"+K+")"+K+"*"),S=new RegExp("="+K+"*([^\\]'\"]*?)"+K+"*\\]","g"),T=new RegExp(N),U=new RegExp("^"+L+"$"),V={ID:new RegExp("^#("+L+")"),CLASS:new RegExp("^\\.("+L+")"),TAG:new RegExp("^("+L+"|[*])"),ATTR:new RegExp("^"+M),PSEUDO:new RegExp("^"+N),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+K+"*(even|odd|(([+-]|)(\\d*)n|)"+K+"*(?:([+-]|)"+K+"*(\\d+)|))"+K+"*\\)|)","i"),bool:new RegExp("^(?:"+J+")$","i"),needsContext:new RegExp("^"+K+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+K+"*((?:-\\d)?\\d*)"+K+"*\\)|)(?=[^-]|$)","i")},W=/^(?:input|select|textarea|button)$/i,X=/^h\d$/i,Y=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,$=/[+~]/,_=new RegExp("\\\\([\\da-f]{1,6}"+K+"?|("+K+")|.)","ig"),aa=function(a,b,c){var d="0x"+b-65536;return d!==d||c?b:d<0?String.fromCharCode(d+65536):String.fromCharCode(d>>10|55296,1023&d|56320)},ba=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ca=function(a,b){return b?"\0"===a?"\ufffd":a.slice(0,-1)+"\\"+a.charCodeAt(a.length-1).toString(16)+" ":"\\"+a},da=function(){m()},ea=ta(function(a){return a.disabled===!0&&("form"in a||"label"in a)},{dir:"parentNode",next:"legend"});try{G.apply(D=H.call(v.childNodes),v.childNodes),D[v.childNodes.length].nodeType}catch(fa){G={apply:D.length?function(a,b){F.apply(a,H.call(b))}:function(a,b){var c=a.length,d=0;while(a[c++]=b[d++]);a.length=c-1}}}function ga(a,b,d,e){var f,h,j,k,l,o,r,s=b&&b.ownerDocument,w=b?b.nodeType:9;if(d=d||[],"string"!=typeof a||!a||1!==w&&9!==w&&11!==w)return d;if(!e&&((b?b.ownerDocument||b:v)!==n&&m(b),b=b||n,p)){if(11!==w&&(l=Z.exec(a)))if(f=l[1]){if(9===w){if(!(j=b.getElementById(f)))return d;if(j.id===f)return d.push(j),d}else if(s&&(j=s.getElementById(f))&&t(b,j)&&j.id===f)return d.push(j),d}else{if(l[2])return G.apply(d,b.getElementsByTagName(a)),d;if((f=l[3])&&c.getElementsByClassName&&b.getElementsByClassName)return G.apply(d,b.getElementsByClassName(f)),d}if(c.qsa&&!A[a+" "]&&(!q||!q.test(a))){if(1!==w)s=b,r=a;else if("object"!==b.nodeName.toLowerCase()){(k=b.getAttribute("id"))?k=k.replace(ba,ca):b.setAttribute("id",k=u),o=g(a),h=o.length;while(h--)o[h]="#"+k+" "+sa(o[h]);r=o.join(","),s=$.test(a)&&qa(b.parentNode)||b}if(r)try{return G.apply(d,s.querySelectorAll(r)),d}catch(x){}finally{k===u&&b.removeAttribute("id")}}}return i(a.replace(P,"$1"),b,d,e)}function ha(){var a=[];function b(c,e){return a.push(c+" ")>d.cacheLength&&delete b[a.shift()],b[c+" "]=e}return b}function ia(a){return a[u]=!0,a}function ja(a){var b=n.createElement("fieldset");try{return!!a(b)}catch(c){return!1}finally{b.parentNode&&b.parentNode.removeChild(b),b=null}}function ka(a,b){var c=a.split("|"),e=c.length;while(e--)d.attrHandle[c[e]]=b}function la(a,b){var c=b&&a,d=c&&1===a.nodeType&&1===b.nodeType&&a.sourceIndex-b.sourceIndex;if(d)return d;if(c)while(c=c.nextSibling)if(c===b)return-1;return a?1:-1}function ma(a){return function(b){var c=b.nodeName.toLowerCase();return"input"===c&&b.type===a}}function na(a){return function(b){var c=b.nodeName.toLowerCase();return("input"===c||"button"===c)&&b.type===a}}function oa(a){return function(b){return"form"in b?b.parentNode&&b.disabled===!1?"label"in b?"label"in b.parentNode?b.parentNode.disabled===a:b.disabled===a:b.isDisabled===a||b.isDisabled!==!a&&ea(b)===a:b.disabled===a:"label"in b&&b.disabled===a}}function pa(a){return ia(function(b){return b=+b,ia(function(c,d){var e,f=a([],c.length,b),g=f.length;while(g--)c[e=f[g]]&&(c[e]=!(d[e]=c[e]))})})}function qa(a){return a&&"undefined"!=typeof a.getElementsByTagName&&a}c=ga.support={},f=ga.isXML=function(a){var b=a&&(a.ownerDocument||a).documentElement;return!!b&&"HTML"!==b.nodeName},m=ga.setDocument=function(a){var b,e,g=a?a.ownerDocument||a:v;return g!==n&&9===g.nodeType&&g.documentElement?(n=g,o=n.documentElement,p=!f(n),v!==n&&(e=n.defaultView)&&e.top!==e&&(e.addEventListener?e.addEventListener("unload",da,!1):e.attachEvent&&e.attachEvent("onunload",da)),c.attributes=ja(function(a){return a.className="i",!a.getAttribute("className")}),c.getElementsByTagName=ja(function(a){return a.appendChild(n.createComment("")),!a.getElementsByTagName("*").length}),c.getElementsByClassName=Y.test(n.getElementsByClassName),c.getById=ja(function(a){return o.appendChild(a).id=u,!n.getElementsByName||!n.getElementsByName(u).length}),c.getById?(d.filter.ID=function(a){var b=a.replace(_,aa);return function(a){return a.getAttribute("id")===b}},d.find.ID=function(a,b){if("undefined"!=typeof b.getElementById&&p){var c=b.getElementById(a);return c?[c]:[]}}):(d.filter.ID=function(a){var b=a.replace(_,aa);return function(a){var c="undefined"!=typeof a.getAttributeNode&&a.getAttributeNode("id");return c&&c.value===b}},d.find.ID=function(a,b){if("undefined"!=typeof b.getElementById&&p){var c,d,e,f=b.getElementById(a);if(f){if(c=f.getAttributeNode("id"),c&&c.value===a)return[f];e=b.getElementsByName(a),d=0;while(f=e[d++])if(c=f.getAttributeNode("id"),c&&c.value===a)return[f]}return[]}}),d.find.TAG=c.getElementsByTagName?function(a,b){return"undefined"!=typeof b.getElementsByTagName?b.getElementsByTagName(a):c.qsa?b.querySelectorAll(a):void 0}:function(a,b){var c,d=[],e=0,f=b.getElementsByTagName(a);if("*"===a){while(c=f[e++])1===c.nodeType&&d.push(c);return d}return f},d.find.CLASS=c.getElementsByClassName&&function(a,b){if("undefined"!=typeof b.getElementsByClassName&&p)return b.getElementsByClassName(a)},r=[],q=[],(c.qsa=Y.test(n.querySelectorAll))&&(ja(function(a){o.appendChild(a).innerHTML="",a.querySelectorAll("[msallowcapture^='']").length&&q.push("[*^$]="+K+"*(?:''|\"\")"),a.querySelectorAll("[selected]").length||q.push("\\["+K+"*(?:value|"+J+")"),a.querySelectorAll("[id~="+u+"-]").length||q.push("~="),a.querySelectorAll(":checked").length||q.push(":checked"),a.querySelectorAll("a#"+u+"+*").length||q.push(".#.+[+~]")}),ja(function(a){a.innerHTML="";var b=n.createElement("input");b.setAttribute("type","hidden"),a.appendChild(b).setAttribute("name","D"),a.querySelectorAll("[name=d]").length&&q.push("name"+K+"*[*^$|!~]?="),2!==a.querySelectorAll(":enabled").length&&q.push(":enabled",":disabled"),o.appendChild(a).disabled=!0,2!==a.querySelectorAll(":disabled").length&&q.push(":enabled",":disabled"),a.querySelectorAll("*,:x"),q.push(",.*:")})),(c.matchesSelector=Y.test(s=o.matches||o.webkitMatchesSelector||o.mozMatchesSelector||o.oMatchesSelector||o.msMatchesSelector))&&ja(function(a){c.disconnectedMatch=s.call(a,"*"),s.call(a,"[s!='']:x"),r.push("!=",N)}),q=q.length&&new RegExp(q.join("|")),r=r.length&&new RegExp(r.join("|")),b=Y.test(o.compareDocumentPosition),t=b||Y.test(o.contains)?function(a,b){var c=9===a.nodeType?a.documentElement:a,d=b&&b.parentNode;return a===d||!(!d||1!==d.nodeType||!(c.contains?c.contains(d):a.compareDocumentPosition&&16&a.compareDocumentPosition(d)))}:function(a,b){if(b)while(b=b.parentNode)if(b===a)return!0;return!1},B=b?function(a,b){if(a===b)return l=!0,0;var d=!a.compareDocumentPosition-!b.compareDocumentPosition;return d?d:(d=(a.ownerDocument||a)===(b.ownerDocument||b)?a.compareDocumentPosition(b):1,1&d||!c.sortDetached&&b.compareDocumentPosition(a)===d?a===n||a.ownerDocument===v&&t(v,a)?-1:b===n||b.ownerDocument===v&&t(v,b)?1:k?I(k,a)-I(k,b):0:4&d?-1:1)}:function(a,b){if(a===b)return l=!0,0;var c,d=0,e=a.parentNode,f=b.parentNode,g=[a],h=[b];if(!e||!f)return a===n?-1:b===n?1:e?-1:f?1:k?I(k,a)-I(k,b):0;if(e===f)return la(a,b);c=a;while(c=c.parentNode)g.unshift(c);c=b;while(c=c.parentNode)h.unshift(c);while(g[d]===h[d])d++;return d?la(g[d],h[d]):g[d]===v?-1:h[d]===v?1:0},n):n},ga.matches=function(a,b){return ga(a,null,null,b)},ga.matchesSelector=function(a,b){if((a.ownerDocument||a)!==n&&m(a),b=b.replace(S,"='$1']"),c.matchesSelector&&p&&!A[b+" "]&&(!r||!r.test(b))&&(!q||!q.test(b)))try{var d=s.call(a,b);if(d||c.disconnectedMatch||a.document&&11!==a.document.nodeType)return d}catch(e){}return ga(b,n,null,[a]).length>0},ga.contains=function(a,b){return(a.ownerDocument||a)!==n&&m(a),t(a,b)},ga.attr=function(a,b){(a.ownerDocument||a)!==n&&m(a);var e=d.attrHandle[b.toLowerCase()],f=e&&C.call(d.attrHandle,b.toLowerCase())?e(a,b,!p):void 0;return void 0!==f?f:c.attributes||!p?a.getAttribute(b):(f=a.getAttributeNode(b))&&f.specified?f.value:null},ga.escape=function(a){return(a+"").replace(ba,ca)},ga.error=function(a){throw new Error("Syntax error, unrecognized expression: "+a)},ga.uniqueSort=function(a){var b,d=[],e=0,f=0;if(l=!c.detectDuplicates,k=!c.sortStable&&a.slice(0),a.sort(B),l){while(b=a[f++])b===a[f]&&(e=d.push(f));while(e--)a.splice(d[e],1)}return k=null,a},e=ga.getText=function(a){var b,c="",d=0,f=a.nodeType;if(f){if(1===f||9===f||11===f){if("string"==typeof a.textContent)return a.textContent;for(a=a.firstChild;a;a=a.nextSibling)c+=e(a)}else if(3===f||4===f)return a.nodeValue}else while(b=a[d++])c+=e(b);return c},d=ga.selectors={cacheLength:50,createPseudo:ia,match:V,attrHandle:{},find:{},relative:{">":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(a){return a[1]=a[1].replace(_,aa),a[3]=(a[3]||a[4]||a[5]||"").replace(_,aa),"~="===a[2]&&(a[3]=" "+a[3]+" "),a.slice(0,4)},CHILD:function(a){return a[1]=a[1].toLowerCase(),"nth"===a[1].slice(0,3)?(a[3]||ga.error(a[0]),a[4]=+(a[4]?a[5]+(a[6]||1):2*("even"===a[3]||"odd"===a[3])),a[5]=+(a[7]+a[8]||"odd"===a[3])):a[3]&&ga.error(a[0]),a},PSEUDO:function(a){var b,c=!a[6]&&a[2];return V.CHILD.test(a[0])?null:(a[3]?a[2]=a[4]||a[5]||"":c&&T.test(c)&&(b=g(c,!0))&&(b=c.indexOf(")",c.length-b)-c.length)&&(a[0]=a[0].slice(0,b),a[2]=c.slice(0,b)),a.slice(0,3))}},filter:{TAG:function(a){var b=a.replace(_,aa).toLowerCase();return"*"===a?function(){return!0}:function(a){return a.nodeName&&a.nodeName.toLowerCase()===b}},CLASS:function(a){var b=y[a+" "];return b||(b=new RegExp("(^|"+K+")"+a+"("+K+"|$)"))&&y(a,function(a){return b.test("string"==typeof a.className&&a.className||"undefined"!=typeof a.getAttribute&&a.getAttribute("class")||"")})},ATTR:function(a,b,c){return function(d){var e=ga.attr(d,a);return null==e?"!="===b:!b||(e+="","="===b?e===c:"!="===b?e!==c:"^="===b?c&&0===e.indexOf(c):"*="===b?c&&e.indexOf(c)>-1:"$="===b?c&&e.slice(-c.length)===c:"~="===b?(" "+e.replace(O," ")+" ").indexOf(c)>-1:"|="===b&&(e===c||e.slice(0,c.length+1)===c+"-"))}},CHILD:function(a,b,c,d,e){var f="nth"!==a.slice(0,3),g="last"!==a.slice(-4),h="of-type"===b;return 1===d&&0===e?function(a){return!!a.parentNode}:function(b,c,i){var j,k,l,m,n,o,p=f!==g?"nextSibling":"previousSibling",q=b.parentNode,r=h&&b.nodeName.toLowerCase(),s=!i&&!h,t=!1;if(q){if(f){while(p){m=b;while(m=m[p])if(h?m.nodeName.toLowerCase()===r:1===m.nodeType)return!1;o=p="only"===a&&!o&&"nextSibling"}return!0}if(o=[g?q.firstChild:q.lastChild],g&&s){m=q,l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),j=k[a]||[],n=j[0]===w&&j[1],t=n&&j[2],m=n&&q.childNodes[n];while(m=++n&&m&&m[p]||(t=n=0)||o.pop())if(1===m.nodeType&&++t&&m===b){k[a]=[w,n,t];break}}else if(s&&(m=b,l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),j=k[a]||[],n=j[0]===w&&j[1],t=n),t===!1)while(m=++n&&m&&m[p]||(t=n=0)||o.pop())if((h?m.nodeName.toLowerCase()===r:1===m.nodeType)&&++t&&(s&&(l=m[u]||(m[u]={}),k=l[m.uniqueID]||(l[m.uniqueID]={}),k[a]=[w,t]),m===b))break;return t-=e,t===d||t%d===0&&t/d>=0}}},PSEUDO:function(a,b){var c,e=d.pseudos[a]||d.setFilters[a.toLowerCase()]||ga.error("unsupported pseudo: "+a);return e[u]?e(b):e.length>1?(c=[a,a,"",b],d.setFilters.hasOwnProperty(a.toLowerCase())?ia(function(a,c){var d,f=e(a,b),g=f.length;while(g--)d=I(a,f[g]),a[d]=!(c[d]=f[g])}):function(a){return e(a,0,c)}):e}},pseudos:{not:ia(function(a){var b=[],c=[],d=h(a.replace(P,"$1"));return d[u]?ia(function(a,b,c,e){var f,g=d(a,null,e,[]),h=a.length;while(h--)(f=g[h])&&(a[h]=!(b[h]=f))}):function(a,e,f){return b[0]=a,d(b,null,f,c),b[0]=null,!c.pop()}}),has:ia(function(a){return function(b){return ga(a,b).length>0}}),contains:ia(function(a){return a=a.replace(_,aa),function(b){return(b.textContent||b.innerText||e(b)).indexOf(a)>-1}}),lang:ia(function(a){return U.test(a||"")||ga.error("unsupported lang: "+a),a=a.replace(_,aa).toLowerCase(),function(b){var c;do if(c=p?b.lang:b.getAttribute("xml:lang")||b.getAttribute("lang"))return c=c.toLowerCase(),c===a||0===c.indexOf(a+"-");while((b=b.parentNode)&&1===b.nodeType);return!1}}),target:function(b){var c=a.location&&a.location.hash;return c&&c.slice(1)===b.id},root:function(a){return a===o},focus:function(a){return a===n.activeElement&&(!n.hasFocus||n.hasFocus())&&!!(a.type||a.href||~a.tabIndex)},enabled:oa(!1),disabled:oa(!0),checked:function(a){var b=a.nodeName.toLowerCase();return"input"===b&&!!a.checked||"option"===b&&!!a.selected},selected:function(a){return a.parentNode&&a.parentNode.selectedIndex,a.selected===!0},empty:function(a){for(a=a.firstChild;a;a=a.nextSibling)if(a.nodeType<6)return!1;return!0},parent:function(a){return!d.pseudos.empty(a)},header:function(a){return X.test(a.nodeName)},input:function(a){return W.test(a.nodeName)},button:function(a){var b=a.nodeName.toLowerCase();return"input"===b&&"button"===a.type||"button"===b},text:function(a){var b;return"input"===a.nodeName.toLowerCase()&&"text"===a.type&&(null==(b=a.getAttribute("type"))||"text"===b.toLowerCase())},first:pa(function(){return[0]}),last:pa(function(a,b){return[b-1]}),eq:pa(function(a,b,c){return[c<0?c+b:c]}),even:pa(function(a,b){for(var c=0;c=0;)a.push(d);return a}),gt:pa(function(a,b,c){for(var d=c<0?c+b:c;++d1?function(b,c,d){var e=a.length;while(e--)if(!a[e](b,c,d))return!1;return!0}:a[0]}function va(a,b,c){for(var d=0,e=b.length;d-1&&(f[j]=!(g[j]=l))}}else r=wa(r===g?r.splice(o,r.length):r),e?e(null,g,r,i):G.apply(g,r)})}function ya(a){for(var b,c,e,f=a.length,g=d.relative[a[0].type],h=g||d.relative[" "],i=g?1:0,k=ta(function(a){return a===b},h,!0),l=ta(function(a){return I(b,a)>-1},h,!0),m=[function(a,c,d){var e=!g&&(d||c!==j)||((b=c).nodeType?k(a,c,d):l(a,c,d));return b=null,e}];i1&&ua(m),i>1&&sa(a.slice(0,i-1).concat({value:" "===a[i-2].type?"*":""})).replace(P,"$1"),c,i0,e=a.length>0,f=function(f,g,h,i,k){var l,o,q,r=0,s="0",t=f&&[],u=[],v=j,x=f||e&&d.find.TAG("*",k),y=w+=null==v?1:Math.random()||.1,z=x.length;for(k&&(j=g===n||g||k);s!==z&&null!=(l=x[s]);s++){if(e&&l){o=0,g||l.ownerDocument===n||(m(l),h=!p);while(q=a[o++])if(q(l,g||n,h)){i.push(l);break}k&&(w=y)}c&&((l=!q&&l)&&r--,f&&t.push(l))}if(r+=s,c&&s!==r){o=0;while(q=b[o++])q(t,u,g,h);if(f){if(r>0)while(s--)t[s]||u[s]||(u[s]=E.call(i));u=wa(u)}G.apply(i,u),k&&!f&&u.length>0&&r+b.length>1&&ga.uniqueSort(i)}return k&&(w=y,j=v),t};return c?ia(f):f}return h=ga.compile=function(a,b){var c,d=[],e=[],f=A[a+" "];if(!f){b||(b=g(a)),c=b.length;while(c--)f=ya(b[c]),f[u]?d.push(f):e.push(f);f=A(a,za(e,d)),f.selector=a}return f},i=ga.select=function(a,b,c,e){var f,i,j,k,l,m="function"==typeof a&&a,n=!e&&g(a=m.selector||a);if(c=c||[],1===n.length){if(i=n[0]=n[0].slice(0),i.length>2&&"ID"===(j=i[0]).type&&9===b.nodeType&&p&&d.relative[i[1].type]){if(b=(d.find.ID(j.matches[0].replace(_,aa),b)||[])[0],!b)return c;m&&(b=b.parentNode),a=a.slice(i.shift().value.length)}f=V.needsContext.test(a)?0:i.length;while(f--){if(j=i[f],d.relative[k=j.type])break;if((l=d.find[k])&&(e=l(j.matches[0].replace(_,aa),$.test(i[0].type)&&qa(b.parentNode)||b))){if(i.splice(f,1),a=e.length&&sa(i),!a)return G.apply(c,e),c;break}}}return(m||h(a,n))(e,b,!p,c,!b||$.test(a)&&qa(b.parentNode)||b),c},c.sortStable=u.split("").sort(B).join("")===u,c.detectDuplicates=!!l,m(),c.sortDetached=ja(function(a){return 1&a.compareDocumentPosition(n.createElement("fieldset"))}),ja(function(a){return a.innerHTML="","#"===a.firstChild.getAttribute("href")})||ka("type|href|height|width",function(a,b,c){if(!c)return a.getAttribute(b,"type"===b.toLowerCase()?1:2)}),c.attributes&&ja(function(a){return a.innerHTML="",a.firstChild.setAttribute("value",""),""===a.firstChild.getAttribute("value")})||ka("value",function(a,b,c){if(!c&&"input"===a.nodeName.toLowerCase())return a.defaultValue}),ja(function(a){return null==a.getAttribute("disabled")})||ka(J,function(a,b,c){var d;if(!c)return a[b]===!0?b.toLowerCase():(d=a.getAttributeNode(b))&&d.specified?d.value:null}),ga}(a);r.find=x,r.expr=x.selectors,r.expr[":"]=r.expr.pseudos,r.uniqueSort=r.unique=x.uniqueSort,r.text=x.getText,r.isXMLDoc=x.isXML,r.contains=x.contains,r.escapeSelector=x.escape;var y=function(a,b,c){var d=[],e=void 0!==c;while((a=a[b])&&9!==a.nodeType)if(1===a.nodeType){if(e&&r(a).is(c))break;d.push(a)}return d},z=function(a,b){for(var c=[];a;a=a.nextSibling)1===a.nodeType&&a!==b&&c.push(a);return c},A=r.expr.match.needsContext;function B(a,b){return a.nodeName&&a.nodeName.toLowerCase()===b.toLowerCase()}var C=/^<([a-z][^\/\0>:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i,D=/^.[^:#\[\.,]*$/;function E(a,b,c){return r.isFunction(b)?r.grep(a,function(a,d){return!!b.call(a,d,a)!==c}):b.nodeType?r.grep(a,function(a){return a===b!==c}):"string"!=typeof b?r.grep(a,function(a){return i.call(b,a)>-1!==c}):D.test(b)?r.filter(b,a,c):(b=r.filter(b,a),r.grep(a,function(a){return i.call(b,a)>-1!==c&&1===a.nodeType}))}r.filter=function(a,b,c){var d=b[0];return c&&(a=":not("+a+")"),1===b.length&&1===d.nodeType?r.find.matchesSelector(d,a)?[d]:[]:r.find.matches(a,r.grep(b,function(a){return 1===a.nodeType}))},r.fn.extend({find:function(a){var b,c,d=this.length,e=this;if("string"!=typeof a)return this.pushStack(r(a).filter(function(){for(b=0;b1?r.uniqueSort(c):c},filter:function(a){return this.pushStack(E(this,a||[],!1))},not:function(a){return this.pushStack(E(this,a||[],!0))},is:function(a){return!!E(this,"string"==typeof a&&A.test(a)?r(a):a||[],!1).length}});var F,G=/^(?:\s*(<[\w\W]+>)[^>]*|#([\w-]+))$/,H=r.fn.init=function(a,b,c){var e,f;if(!a)return this;if(c=c||F,"string"==typeof a){if(e="<"===a[0]&&">"===a[a.length-1]&&a.length>=3?[null,a,null]:G.exec(a),!e||!e[1]&&b)return!b||b.jquery?(b||c).find(a):this.constructor(b).find(a);if(e[1]){if(b=b instanceof r?b[0]:b,r.merge(this,r.parseHTML(e[1],b&&b.nodeType?b.ownerDocument||b:d,!0)),C.test(e[1])&&r.isPlainObject(b))for(e in b)r.isFunction(this[e])?this[e](b[e]):this.attr(e,b[e]);return this}return f=d.getElementById(e[2]),f&&(this[0]=f,this.length=1),this}return a.nodeType?(this[0]=a,this.length=1,this):r.isFunction(a)?void 0!==c.ready?c.ready(a):a(r):r.makeArray(a,this)};H.prototype=r.fn,F=r(d);var I=/^(?:parents|prev(?:Until|All))/,J={children:!0,contents:!0,next:!0,prev:!0};r.fn.extend({has:function(a){var b=r(a,this),c=b.length;return this.filter(function(){for(var a=0;a-1:1===c.nodeType&&r.find.matchesSelector(c,a))){f.push(c);break}return this.pushStack(f.length>1?r.uniqueSort(f):f)},index:function(a){return a?"string"==typeof a?i.call(r(a),this[0]):i.call(this,a.jquery?a[0]:a):this[0]&&this[0].parentNode?this.first().prevAll().length:-1},add:function(a,b){return this.pushStack(r.uniqueSort(r.merge(this.get(),r(a,b))))},addBack:function(a){return this.add(null==a?this.prevObject:this.prevObject.filter(a))}});function K(a,b){while((a=a[b])&&1!==a.nodeType);return a}r.each({parent:function(a){var b=a.parentNode;return b&&11!==b.nodeType?b:null},parents:function(a){return y(a,"parentNode")},parentsUntil:function(a,b,c){return y(a,"parentNode",c)},next:function(a){return K(a,"nextSibling")},prev:function(a){return K(a,"previousSibling")},nextAll:function(a){return y(a,"nextSibling")},prevAll:function(a){return y(a,"previousSibling")},nextUntil:function(a,b,c){return y(a,"nextSibling",c)},prevUntil:function(a,b,c){return y(a,"previousSibling",c)},siblings:function(a){return z((a.parentNode||{}).firstChild,a)},children:function(a){return z(a.firstChild)},contents:function(a){return B(a,"iframe")?a.contentDocument:(B(a,"template")&&(a=a.content||a),r.merge([],a.childNodes))}},function(a,b){r.fn[a]=function(c,d){var e=r.map(this,b,c);return"Until"!==a.slice(-5)&&(d=c),d&&"string"==typeof d&&(e=r.filter(d,e)),this.length>1&&(J[a]||r.uniqueSort(e),I.test(a)&&e.reverse()),this.pushStack(e)}});var L=/[^\x20\t\r\n\f]+/g;function M(a){var b={};return r.each(a.match(L)||[],function(a,c){b[c]=!0}),b}r.Callbacks=function(a){a="string"==typeof a?M(a):r.extend({},a);var b,c,d,e,f=[],g=[],h=-1,i=function(){for(e=e||a.once,d=b=!0;g.length;h=-1){c=g.shift();while(++h-1)f.splice(c,1),c<=h&&h--}),this},has:function(a){return a?r.inArray(a,f)>-1:f.length>0},empty:function(){return f&&(f=[]),this},disable:function(){return e=g=[],f=c="",this},disabled:function(){return!f},lock:function(){return e=g=[],c||b||(f=c=""),this},locked:function(){return!!e},fireWith:function(a,c){return e||(c=c||[],c=[a,c.slice?c.slice():c],g.push(c),b||i()),this},fire:function(){return j.fireWith(this,arguments),this},fired:function(){return!!d}};return j};function N(a){return a}function O(a){throw a}function P(a,b,c,d){var e;try{a&&r.isFunction(e=a.promise)?e.call(a).done(b).fail(c):a&&r.isFunction(e=a.then)?e.call(a,b,c):b.apply(void 0,[a].slice(d))}catch(a){c.apply(void 0,[a])}}r.extend({Deferred:function(b){var c=[["notify","progress",r.Callbacks("memory"),r.Callbacks("memory"),2],["resolve","done",r.Callbacks("once memory"),r.Callbacks("once memory"),0,"resolved"],["reject","fail",r.Callbacks("once memory"),r.Callbacks("once memory"),1,"rejected"]],d="pending",e={state:function(){return d},always:function(){return f.done(arguments).fail(arguments),this},"catch":function(a){return e.then(null,a)},pipe:function(){var a=arguments;return r.Deferred(function(b){r.each(c,function(c,d){var e=r.isFunction(a[d[4]])&&a[d[4]];f[d[1]](function(){var a=e&&e.apply(this,arguments);a&&r.isFunction(a.promise)?a.promise().progress(b.notify).done(b.resolve).fail(b.reject):b[d[0]+"With"](this,e?[a]:arguments)})}),a=null}).promise()},then:function(b,d,e){var f=0;function g(b,c,d,e){return function(){var h=this,i=arguments,j=function(){var a,j;if(!(b=f&&(d!==O&&(h=void 0,i=[a]),c.rejectWith(h,i))}};b?k():(r.Deferred.getStackHook&&(k.stackTrace=r.Deferred.getStackHook()),a.setTimeout(k))}}return r.Deferred(function(a){c[0][3].add(g(0,a,r.isFunction(e)?e:N,a.notifyWith)),c[1][3].add(g(0,a,r.isFunction(b)?b:N)),c[2][3].add(g(0,a,r.isFunction(d)?d:O))}).promise()},promise:function(a){return null!=a?r.extend(a,e):e}},f={};return r.each(c,function(a,b){var g=b[2],h=b[5];e[b[1]]=g.add,h&&g.add(function(){d=h},c[3-a][2].disable,c[0][2].lock),g.add(b[3].fire),f[b[0]]=function(){return f[b[0]+"With"](this===f?void 0:this,arguments),this},f[b[0]+"With"]=g.fireWith}),e.promise(f),b&&b.call(f,f),f},when:function(a){var b=arguments.length,c=b,d=Array(c),e=f.call(arguments),g=r.Deferred(),h=function(a){return function(c){d[a]=this,e[a]=arguments.length>1?f.call(arguments):c,--b||g.resolveWith(d,e)}};if(b<=1&&(P(a,g.done(h(c)).resolve,g.reject,!b),"pending"===g.state()||r.isFunction(e[c]&&e[c].then)))return g.then();while(c--)P(e[c],h(c),g.reject);return g.promise()}});var Q=/^(Eval|Internal|Range|Reference|Syntax|Type|URI)Error$/;r.Deferred.exceptionHook=function(b,c){a.console&&a.console.warn&&b&&Q.test(b.name)&&a.console.warn("jQuery.Deferred exception: "+b.message,b.stack,c)},r.readyException=function(b){a.setTimeout(function(){throw b})};var R=r.Deferred();r.fn.ready=function(a){return R.then(a)["catch"](function(a){r.readyException(a)}),this},r.extend({isReady:!1,readyWait:1,ready:function(a){(a===!0?--r.readyWait:r.isReady)||(r.isReady=!0,a!==!0&&--r.readyWait>0||R.resolveWith(d,[r]))}}),r.ready.then=R.then;function S(){d.removeEventListener("DOMContentLoaded",S), +a.removeEventListener("load",S),r.ready()}"complete"===d.readyState||"loading"!==d.readyState&&!d.documentElement.doScroll?a.setTimeout(r.ready):(d.addEventListener("DOMContentLoaded",S),a.addEventListener("load",S));var T=function(a,b,c,d,e,f,g){var h=0,i=a.length,j=null==c;if("object"===r.type(c)){e=!0;for(h in c)T(a,b,h,c[h],!0,f,g)}else if(void 0!==d&&(e=!0,r.isFunction(d)||(g=!0),j&&(g?(b.call(a,d),b=null):(j=b,b=function(a,b,c){return j.call(r(a),c)})),b))for(;h1,null,!0)},removeData:function(a){return this.each(function(){X.remove(this,a)})}}),r.extend({queue:function(a,b,c){var d;if(a)return b=(b||"fx")+"queue",d=W.get(a,b),c&&(!d||Array.isArray(c)?d=W.access(a,b,r.makeArray(c)):d.push(c)),d||[]},dequeue:function(a,b){b=b||"fx";var c=r.queue(a,b),d=c.length,e=c.shift(),f=r._queueHooks(a,b),g=function(){r.dequeue(a,b)};"inprogress"===e&&(e=c.shift(),d--),e&&("fx"===b&&c.unshift("inprogress"),delete f.stop,e.call(a,g,f)),!d&&f&&f.empty.fire()},_queueHooks:function(a,b){var c=b+"queueHooks";return W.get(a,c)||W.access(a,c,{empty:r.Callbacks("once memory").add(function(){W.remove(a,[b+"queue",c])})})}}),r.fn.extend({queue:function(a,b){var c=2;return"string"!=typeof a&&(b=a,a="fx",c--),arguments.length\x20\t\r\n\f]+)/i,la=/^$|\/(?:java|ecma)script/i,ma={option:[1,""],thead:[1,"","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};ma.optgroup=ma.option,ma.tbody=ma.tfoot=ma.colgroup=ma.caption=ma.thead,ma.th=ma.td;function na(a,b){var c;return c="undefined"!=typeof a.getElementsByTagName?a.getElementsByTagName(b||"*"):"undefined"!=typeof a.querySelectorAll?a.querySelectorAll(b||"*"):[],void 0===b||b&&B(a,b)?r.merge([a],c):c}function oa(a,b){for(var c=0,d=a.length;c-1)e&&e.push(f);else if(j=r.contains(f.ownerDocument,f),g=na(l.appendChild(f),"script"),j&&oa(g),c){k=0;while(f=g[k++])la.test(f.type||"")&&c.push(f)}return l}!function(){var a=d.createDocumentFragment(),b=a.appendChild(d.createElement("div")),c=d.createElement("input");c.setAttribute("type","radio"),c.setAttribute("checked","checked"),c.setAttribute("name","t"),b.appendChild(c),o.checkClone=b.cloneNode(!0).cloneNode(!0).lastChild.checked,b.innerHTML="",o.noCloneChecked=!!b.cloneNode(!0).lastChild.defaultValue}();var ra=d.documentElement,sa=/^key/,ta=/^(?:mouse|pointer|contextmenu|drag|drop)|click/,ua=/^([^.]*)(?:\.(.+)|)/;function va(){return!0}function wa(){return!1}function xa(){try{return d.activeElement}catch(a){}}function ya(a,b,c,d,e,f){var g,h;if("object"==typeof b){"string"!=typeof c&&(d=d||c,c=void 0);for(h in b)ya(a,h,c,d,b[h],f);return a}if(null==d&&null==e?(e=c,d=c=void 0):null==e&&("string"==typeof c?(e=d,d=void 0):(e=d,d=c,c=void 0)),e===!1)e=wa;else if(!e)return a;return 1===f&&(g=e,e=function(a){return r().off(a),g.apply(this,arguments)},e.guid=g.guid||(g.guid=r.guid++)),a.each(function(){r.event.add(this,b,e,d,c)})}r.event={global:{},add:function(a,b,c,d,e){var f,g,h,i,j,k,l,m,n,o,p,q=W.get(a);if(q){c.handler&&(f=c,c=f.handler,e=f.selector),e&&r.find.matchesSelector(ra,e),c.guid||(c.guid=r.guid++),(i=q.events)||(i=q.events={}),(g=q.handle)||(g=q.handle=function(b){return"undefined"!=typeof r&&r.event.triggered!==b.type?r.event.dispatch.apply(a,arguments):void 0}),b=(b||"").match(L)||[""],j=b.length;while(j--)h=ua.exec(b[j])||[],n=p=h[1],o=(h[2]||"").split(".").sort(),n&&(l=r.event.special[n]||{},n=(e?l.delegateType:l.bindType)||n,l=r.event.special[n]||{},k=r.extend({type:n,origType:p,data:d,handler:c,guid:c.guid,selector:e,needsContext:e&&r.expr.match.needsContext.test(e),namespace:o.join(".")},f),(m=i[n])||(m=i[n]=[],m.delegateCount=0,l.setup&&l.setup.call(a,d,o,g)!==!1||a.addEventListener&&a.addEventListener(n,g)),l.add&&(l.add.call(a,k),k.handler.guid||(k.handler.guid=c.guid)),e?m.splice(m.delegateCount++,0,k):m.push(k),r.event.global[n]=!0)}},remove:function(a,b,c,d,e){var f,g,h,i,j,k,l,m,n,o,p,q=W.hasData(a)&&W.get(a);if(q&&(i=q.events)){b=(b||"").match(L)||[""],j=b.length;while(j--)if(h=ua.exec(b[j])||[],n=p=h[1],o=(h[2]||"").split(".").sort(),n){l=r.event.special[n]||{},n=(d?l.delegateType:l.bindType)||n,m=i[n]||[],h=h[2]&&new RegExp("(^|\\.)"+o.join("\\.(?:.*\\.|)")+"(\\.|$)"),g=f=m.length;while(f--)k=m[f],!e&&p!==k.origType||c&&c.guid!==k.guid||h&&!h.test(k.namespace)||d&&d!==k.selector&&("**"!==d||!k.selector)||(m.splice(f,1),k.selector&&m.delegateCount--,l.remove&&l.remove.call(a,k));g&&!m.length&&(l.teardown&&l.teardown.call(a,o,q.handle)!==!1||r.removeEvent(a,n,q.handle),delete i[n])}else for(n in i)r.event.remove(a,n+b[j],c,d,!0);r.isEmptyObject(i)&&W.remove(a,"handle events")}},dispatch:function(a){var b=r.event.fix(a),c,d,e,f,g,h,i=new Array(arguments.length),j=(W.get(this,"events")||{})[b.type]||[],k=r.event.special[b.type]||{};for(i[0]=b,c=1;c=1))for(;j!==this;j=j.parentNode||this)if(1===j.nodeType&&("click"!==a.type||j.disabled!==!0)){for(f=[],g={},c=0;c-1:r.find(e,this,null,[j]).length),g[e]&&f.push(d);f.length&&h.push({elem:j,handlers:f})}return j=this,i\x20\t\r\n\f]*)[^>]*)\/>/gi,Aa=/\s*$/g;function Ea(a,b){return B(a,"table")&&B(11!==b.nodeType?b:b.firstChild,"tr")?r(">tbody",a)[0]||a:a}function Fa(a){return a.type=(null!==a.getAttribute("type"))+"/"+a.type,a}function Ga(a){var b=Ca.exec(a.type);return b?a.type=b[1]:a.removeAttribute("type"),a}function Ha(a,b){var c,d,e,f,g,h,i,j;if(1===b.nodeType){if(W.hasData(a)&&(f=W.access(a),g=W.set(b,f),j=f.events)){delete g.handle,g.events={};for(e in j)for(c=0,d=j[e].length;c1&&"string"==typeof q&&!o.checkClone&&Ba.test(q))return a.each(function(e){var f=a.eq(e);s&&(b[0]=q.call(this,e,f.html())),Ja(f,b,c,d)});if(m&&(e=qa(b,a[0].ownerDocument,!1,a,d),f=e.firstChild,1===e.childNodes.length&&(e=f),f||d)){for(h=r.map(na(e,"script"),Fa),i=h.length;l")},clone:function(a,b,c){var d,e,f,g,h=a.cloneNode(!0),i=r.contains(a.ownerDocument,a);if(!(o.noCloneChecked||1!==a.nodeType&&11!==a.nodeType||r.isXMLDoc(a)))for(g=na(h),f=na(a),d=0,e=f.length;d0&&oa(g,!i&&na(a,"script")),h},cleanData:function(a){for(var b,c,d,e=r.event.special,f=0;void 0!==(c=a[f]);f++)if(U(c)){if(b=c[W.expando]){if(b.events)for(d in b.events)e[d]?r.event.remove(c,d):r.removeEvent(c,d,b.handle);c[W.expando]=void 0}c[X.expando]&&(c[X.expando]=void 0)}}}),r.fn.extend({detach:function(a){return Ka(this,a,!0)},remove:function(a){return Ka(this,a)},text:function(a){return T(this,function(a){return void 0===a?r.text(this):this.empty().each(function(){1!==this.nodeType&&11!==this.nodeType&&9!==this.nodeType||(this.textContent=a)})},null,a,arguments.length)},append:function(){return Ja(this,arguments,function(a){if(1===this.nodeType||11===this.nodeType||9===this.nodeType){var b=Ea(this,a);b.appendChild(a)}})},prepend:function(){return Ja(this,arguments,function(a){if(1===this.nodeType||11===this.nodeType||9===this.nodeType){var b=Ea(this,a);b.insertBefore(a,b.firstChild)}})},before:function(){return Ja(this,arguments,function(a){this.parentNode&&this.parentNode.insertBefore(a,this)})},after:function(){return Ja(this,arguments,function(a){this.parentNode&&this.parentNode.insertBefore(a,this.nextSibling)})},empty:function(){for(var a,b=0;null!=(a=this[b]);b++)1===a.nodeType&&(r.cleanData(na(a,!1)),a.textContent="");return this},clone:function(a,b){return a=null!=a&&a,b=null==b?a:b,this.map(function(){return r.clone(this,a,b)})},html:function(a){return T(this,function(a){var b=this[0]||{},c=0,d=this.length;if(void 0===a&&1===b.nodeType)return b.innerHTML;if("string"==typeof a&&!Aa.test(a)&&!ma[(ka.exec(a)||["",""])[1].toLowerCase()]){a=r.htmlPrefilter(a);try{for(;c1)}});function _a(a,b,c,d,e){return new _a.prototype.init(a,b,c,d,e)}r.Tween=_a,_a.prototype={constructor:_a,init:function(a,b,c,d,e,f){this.elem=a,this.prop=c,this.easing=e||r.easing._default,this.options=b,this.start=this.now=this.cur(),this.end=d,this.unit=f||(r.cssNumber[c]?"":"px")},cur:function(){var a=_a.propHooks[this.prop];return a&&a.get?a.get(this):_a.propHooks._default.get(this)},run:function(a){var b,c=_a.propHooks[this.prop];return this.options.duration?this.pos=b=r.easing[this.easing](a,this.options.duration*a,0,1,this.options.duration):this.pos=b=a,this.now=(this.end-this.start)*b+this.start,this.options.step&&this.options.step.call(this.elem,this.now,this),c&&c.set?c.set(this):_a.propHooks._default.set(this),this}},_a.prototype.init.prototype=_a.prototype,_a.propHooks={_default:{get:function(a){var b;return 1!==a.elem.nodeType||null!=a.elem[a.prop]&&null==a.elem.style[a.prop]?a.elem[a.prop]:(b=r.css(a.elem,a.prop,""),b&&"auto"!==b?b:0)},set:function(a){r.fx.step[a.prop]?r.fx.step[a.prop](a):1!==a.elem.nodeType||null==a.elem.style[r.cssProps[a.prop]]&&!r.cssHooks[a.prop]?a.elem[a.prop]=a.now:r.style(a.elem,a.prop,a.now+a.unit)}}},_a.propHooks.scrollTop=_a.propHooks.scrollLeft={set:function(a){a.elem.nodeType&&a.elem.parentNode&&(a.elem[a.prop]=a.now)}},r.easing={linear:function(a){return a},swing:function(a){return.5-Math.cos(a*Math.PI)/2},_default:"swing"},r.fx=_a.prototype.init,r.fx.step={};var ab,bb,cb=/^(?:toggle|show|hide)$/,db=/queueHooks$/;function eb(){bb&&(d.hidden===!1&&a.requestAnimationFrame?a.requestAnimationFrame(eb):a.setTimeout(eb,r.fx.interval),r.fx.tick())}function fb(){return a.setTimeout(function(){ab=void 0}),ab=r.now()}function gb(a,b){var c,d=0,e={height:a};for(b=b?1:0;d<4;d+=2-b)c=ca[d],e["margin"+c]=e["padding"+c]=a;return b&&(e.opacity=e.width=a),e}function hb(a,b,c){for(var d,e=(kb.tweeners[b]||[]).concat(kb.tweeners["*"]),f=0,g=e.length;f1)},removeAttr:function(a){return this.each(function(){r.removeAttr(this,a)})}}),r.extend({attr:function(a,b,c){var d,e,f=a.nodeType;if(3!==f&&8!==f&&2!==f)return"undefined"==typeof a.getAttribute?r.prop(a,b,c):(1===f&&r.isXMLDoc(a)||(e=r.attrHooks[b.toLowerCase()]||(r.expr.match.bool.test(b)?lb:void 0)),void 0!==c?null===c?void r.removeAttr(a,b):e&&"set"in e&&void 0!==(d=e.set(a,c,b))?d:(a.setAttribute(b,c+""),c):e&&"get"in e&&null!==(d=e.get(a,b))?d:(d=r.find.attr(a,b), +null==d?void 0:d))},attrHooks:{type:{set:function(a,b){if(!o.radioValue&&"radio"===b&&B(a,"input")){var c=a.value;return a.setAttribute("type",b),c&&(a.value=c),b}}}},removeAttr:function(a,b){var c,d=0,e=b&&b.match(L);if(e&&1===a.nodeType)while(c=e[d++])a.removeAttribute(c)}}),lb={set:function(a,b,c){return b===!1?r.removeAttr(a,c):a.setAttribute(c,c),c}},r.each(r.expr.match.bool.source.match(/\w+/g),function(a,b){var c=mb[b]||r.find.attr;mb[b]=function(a,b,d){var e,f,g=b.toLowerCase();return d||(f=mb[g],mb[g]=e,e=null!=c(a,b,d)?g:null,mb[g]=f),e}});var nb=/^(?:input|select|textarea|button)$/i,ob=/^(?:a|area)$/i;r.fn.extend({prop:function(a,b){return T(this,r.prop,a,b,arguments.length>1)},removeProp:function(a){return this.each(function(){delete this[r.propFix[a]||a]})}}),r.extend({prop:function(a,b,c){var d,e,f=a.nodeType;if(3!==f&&8!==f&&2!==f)return 1===f&&r.isXMLDoc(a)||(b=r.propFix[b]||b,e=r.propHooks[b]),void 0!==c?e&&"set"in e&&void 0!==(d=e.set(a,c,b))?d:a[b]=c:e&&"get"in e&&null!==(d=e.get(a,b))?d:a[b]},propHooks:{tabIndex:{get:function(a){var b=r.find.attr(a,"tabindex");return b?parseInt(b,10):nb.test(a.nodeName)||ob.test(a.nodeName)&&a.href?0:-1}}},propFix:{"for":"htmlFor","class":"className"}}),o.optSelected||(r.propHooks.selected={get:function(a){var b=a.parentNode;return b&&b.parentNode&&b.parentNode.selectedIndex,null},set:function(a){var b=a.parentNode;b&&(b.selectedIndex,b.parentNode&&b.parentNode.selectedIndex)}}),r.each(["tabIndex","readOnly","maxLength","cellSpacing","cellPadding","rowSpan","colSpan","useMap","frameBorder","contentEditable"],function(){r.propFix[this.toLowerCase()]=this});function pb(a){var b=a.match(L)||[];return b.join(" ")}function qb(a){return a.getAttribute&&a.getAttribute("class")||""}r.fn.extend({addClass:function(a){var b,c,d,e,f,g,h,i=0;if(r.isFunction(a))return this.each(function(b){r(this).addClass(a.call(this,b,qb(this)))});if("string"==typeof a&&a){b=a.match(L)||[];while(c=this[i++])if(e=qb(c),d=1===c.nodeType&&" "+pb(e)+" "){g=0;while(f=b[g++])d.indexOf(" "+f+" ")<0&&(d+=f+" ");h=pb(d),e!==h&&c.setAttribute("class",h)}}return this},removeClass:function(a){var b,c,d,e,f,g,h,i=0;if(r.isFunction(a))return this.each(function(b){r(this).removeClass(a.call(this,b,qb(this)))});if(!arguments.length)return this.attr("class","");if("string"==typeof a&&a){b=a.match(L)||[];while(c=this[i++])if(e=qb(c),d=1===c.nodeType&&" "+pb(e)+" "){g=0;while(f=b[g++])while(d.indexOf(" "+f+" ")>-1)d=d.replace(" "+f+" "," ");h=pb(d),e!==h&&c.setAttribute("class",h)}}return this},toggleClass:function(a,b){var c=typeof a;return"boolean"==typeof b&&"string"===c?b?this.addClass(a):this.removeClass(a):r.isFunction(a)?this.each(function(c){r(this).toggleClass(a.call(this,c,qb(this),b),b)}):this.each(function(){var b,d,e,f;if("string"===c){d=0,e=r(this),f=a.match(L)||[];while(b=f[d++])e.hasClass(b)?e.removeClass(b):e.addClass(b)}else void 0!==a&&"boolean"!==c||(b=qb(this),b&&W.set(this,"__className__",b),this.setAttribute&&this.setAttribute("class",b||a===!1?"":W.get(this,"__className__")||""))})},hasClass:function(a){var b,c,d=0;b=" "+a+" ";while(c=this[d++])if(1===c.nodeType&&(" "+pb(qb(c))+" ").indexOf(b)>-1)return!0;return!1}});var rb=/\r/g;r.fn.extend({val:function(a){var b,c,d,e=this[0];{if(arguments.length)return d=r.isFunction(a),this.each(function(c){var e;1===this.nodeType&&(e=d?a.call(this,c,r(this).val()):a,null==e?e="":"number"==typeof e?e+="":Array.isArray(e)&&(e=r.map(e,function(a){return null==a?"":a+""})),b=r.valHooks[this.type]||r.valHooks[this.nodeName.toLowerCase()],b&&"set"in b&&void 0!==b.set(this,e,"value")||(this.value=e))});if(e)return b=r.valHooks[e.type]||r.valHooks[e.nodeName.toLowerCase()],b&&"get"in b&&void 0!==(c=b.get(e,"value"))?c:(c=e.value,"string"==typeof c?c.replace(rb,""):null==c?"":c)}}}),r.extend({valHooks:{option:{get:function(a){var b=r.find.attr(a,"value");return null!=b?b:pb(r.text(a))}},select:{get:function(a){var b,c,d,e=a.options,f=a.selectedIndex,g="select-one"===a.type,h=g?null:[],i=g?f+1:e.length;for(d=f<0?i:g?f:0;d-1)&&(c=!0);return c||(a.selectedIndex=-1),f}}}}),r.each(["radio","checkbox"],function(){r.valHooks[this]={set:function(a,b){if(Array.isArray(b))return a.checked=r.inArray(r(a).val(),b)>-1}},o.checkOn||(r.valHooks[this].get=function(a){return null===a.getAttribute("value")?"on":a.value})});var sb=/^(?:focusinfocus|focusoutblur)$/;r.extend(r.event,{trigger:function(b,c,e,f){var g,h,i,j,k,m,n,o=[e||d],p=l.call(b,"type")?b.type:b,q=l.call(b,"namespace")?b.namespace.split("."):[];if(h=i=e=e||d,3!==e.nodeType&&8!==e.nodeType&&!sb.test(p+r.event.triggered)&&(p.indexOf(".")>-1&&(q=p.split("."),p=q.shift(),q.sort()),k=p.indexOf(":")<0&&"on"+p,b=b[r.expando]?b:new r.Event(p,"object"==typeof b&&b),b.isTrigger=f?2:3,b.namespace=q.join("."),b.rnamespace=b.namespace?new RegExp("(^|\\.)"+q.join("\\.(?:.*\\.|)")+"(\\.|$)"):null,b.result=void 0,b.target||(b.target=e),c=null==c?[b]:r.makeArray(c,[b]),n=r.event.special[p]||{},f||!n.trigger||n.trigger.apply(e,c)!==!1)){if(!f&&!n.noBubble&&!r.isWindow(e)){for(j=n.delegateType||p,sb.test(j+p)||(h=h.parentNode);h;h=h.parentNode)o.push(h),i=h;i===(e.ownerDocument||d)&&o.push(i.defaultView||i.parentWindow||a)}g=0;while((h=o[g++])&&!b.isPropagationStopped())b.type=g>1?j:n.bindType||p,m=(W.get(h,"events")||{})[b.type]&&W.get(h,"handle"),m&&m.apply(h,c),m=k&&h[k],m&&m.apply&&U(h)&&(b.result=m.apply(h,c),b.result===!1&&b.preventDefault());return b.type=p,f||b.isDefaultPrevented()||n._default&&n._default.apply(o.pop(),c)!==!1||!U(e)||k&&r.isFunction(e[p])&&!r.isWindow(e)&&(i=e[k],i&&(e[k]=null),r.event.triggered=p,e[p](),r.event.triggered=void 0,i&&(e[k]=i)),b.result}},simulate:function(a,b,c){var d=r.extend(new r.Event,c,{type:a,isSimulated:!0});r.event.trigger(d,null,b)}}),r.fn.extend({trigger:function(a,b){return this.each(function(){r.event.trigger(a,b,this)})},triggerHandler:function(a,b){var c=this[0];if(c)return r.event.trigger(a,b,c,!0)}}),r.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(a,b){r.fn[b]=function(a,c){return arguments.length>0?this.on(b,null,a,c):this.trigger(b)}}),r.fn.extend({hover:function(a,b){return this.mouseenter(a).mouseleave(b||a)}}),o.focusin="onfocusin"in a,o.focusin||r.each({focus:"focusin",blur:"focusout"},function(a,b){var c=function(a){r.event.simulate(b,a.target,r.event.fix(a))};r.event.special[b]={setup:function(){var d=this.ownerDocument||this,e=W.access(d,b);e||d.addEventListener(a,c,!0),W.access(d,b,(e||0)+1)},teardown:function(){var d=this.ownerDocument||this,e=W.access(d,b)-1;e?W.access(d,b,e):(d.removeEventListener(a,c,!0),W.remove(d,b))}}});var tb=a.location,ub=r.now(),vb=/\?/;r.parseXML=function(b){var c;if(!b||"string"!=typeof b)return null;try{c=(new a.DOMParser).parseFromString(b,"text/xml")}catch(d){c=void 0}return c&&!c.getElementsByTagName("parsererror").length||r.error("Invalid XML: "+b),c};var wb=/\[\]$/,xb=/\r?\n/g,yb=/^(?:submit|button|image|reset|file)$/i,zb=/^(?:input|select|textarea|keygen)/i;function Ab(a,b,c,d){var e;if(Array.isArray(b))r.each(b,function(b,e){c||wb.test(a)?d(a,e):Ab(a+"["+("object"==typeof e&&null!=e?b:"")+"]",e,c,d)});else if(c||"object"!==r.type(b))d(a,b);else for(e in b)Ab(a+"["+e+"]",b[e],c,d)}r.param=function(a,b){var c,d=[],e=function(a,b){var c=r.isFunction(b)?b():b;d[d.length]=encodeURIComponent(a)+"="+encodeURIComponent(null==c?"":c)};if(Array.isArray(a)||a.jquery&&!r.isPlainObject(a))r.each(a,function(){e(this.name,this.value)});else for(c in a)Ab(c,a[c],b,e);return d.join("&")},r.fn.extend({serialize:function(){return r.param(this.serializeArray())},serializeArray:function(){return this.map(function(){var a=r.prop(this,"elements");return a?r.makeArray(a):this}).filter(function(){var a=this.type;return this.name&&!r(this).is(":disabled")&&zb.test(this.nodeName)&&!yb.test(a)&&(this.checked||!ja.test(a))}).map(function(a,b){var c=r(this).val();return null==c?null:Array.isArray(c)?r.map(c,function(a){return{name:b.name,value:a.replace(xb,"\r\n")}}):{name:b.name,value:c.replace(xb,"\r\n")}}).get()}});var Bb=/%20/g,Cb=/#.*$/,Db=/([?&])_=[^&]*/,Eb=/^(.*?):[ \t]*([^\r\n]*)$/gm,Fb=/^(?:about|app|app-storage|.+-extension|file|res|widget):$/,Gb=/^(?:GET|HEAD)$/,Hb=/^\/\//,Ib={},Jb={},Kb="*/".concat("*"),Lb=d.createElement("a");Lb.href=tb.href;function Mb(a){return function(b,c){"string"!=typeof b&&(c=b,b="*");var d,e=0,f=b.toLowerCase().match(L)||[];if(r.isFunction(c))while(d=f[e++])"+"===d[0]?(d=d.slice(1)||"*",(a[d]=a[d]||[]).unshift(c)):(a[d]=a[d]||[]).push(c)}}function Nb(a,b,c,d){var e={},f=a===Jb;function g(h){var i;return e[h]=!0,r.each(a[h]||[],function(a,h){var j=h(b,c,d);return"string"!=typeof j||f||e[j]?f?!(i=j):void 0:(b.dataTypes.unshift(j),g(j),!1)}),i}return g(b.dataTypes[0])||!e["*"]&&g("*")}function Ob(a,b){var c,d,e=r.ajaxSettings.flatOptions||{};for(c in b)void 0!==b[c]&&((e[c]?a:d||(d={}))[c]=b[c]);return d&&r.extend(!0,a,d),a}function Pb(a,b,c){var d,e,f,g,h=a.contents,i=a.dataTypes;while("*"===i[0])i.shift(),void 0===d&&(d=a.mimeType||b.getResponseHeader("Content-Type"));if(d)for(e in h)if(h[e]&&h[e].test(d)){i.unshift(e);break}if(i[0]in c)f=i[0];else{for(e in c){if(!i[0]||a.converters[e+" "+i[0]]){f=e;break}g||(g=e)}f=f||g}if(f)return f!==i[0]&&i.unshift(f),c[f]}function Qb(a,b,c,d){var e,f,g,h,i,j={},k=a.dataTypes.slice();if(k[1])for(g in a.converters)j[g.toLowerCase()]=a.converters[g];f=k.shift();while(f)if(a.responseFields[f]&&(c[a.responseFields[f]]=b),!i&&d&&a.dataFilter&&(b=a.dataFilter(b,a.dataType)),i=f,f=k.shift())if("*"===f)f=i;else if("*"!==i&&i!==f){if(g=j[i+" "+f]||j["* "+f],!g)for(e in j)if(h=e.split(" "),h[1]===f&&(g=j[i+" "+h[0]]||j["* "+h[0]])){g===!0?g=j[e]:j[e]!==!0&&(f=h[0],k.unshift(h[1]));break}if(g!==!0)if(g&&a["throws"])b=g(b);else try{b=g(b)}catch(l){return{state:"parsererror",error:g?l:"No conversion from "+i+" to "+f}}}return{state:"success",data:b}}r.extend({active:0,lastModified:{},etag:{},ajaxSettings:{url:tb.href,type:"GET",isLocal:Fb.test(tb.protocol),global:!0,processData:!0,async:!0,contentType:"application/x-www-form-urlencoded; charset=UTF-8",accepts:{"*":Kb,text:"text/plain",html:"text/html",xml:"application/xml, text/xml",json:"application/json, text/javascript"},contents:{xml:/\bxml\b/,html:/\bhtml/,json:/\bjson\b/},responseFields:{xml:"responseXML",text:"responseText",json:"responseJSON"},converters:{"* text":String,"text html":!0,"text json":JSON.parse,"text xml":r.parseXML},flatOptions:{url:!0,context:!0}},ajaxSetup:function(a,b){return b?Ob(Ob(a,r.ajaxSettings),b):Ob(r.ajaxSettings,a)},ajaxPrefilter:Mb(Ib),ajaxTransport:Mb(Jb),ajax:function(b,c){"object"==typeof b&&(c=b,b=void 0),c=c||{};var e,f,g,h,i,j,k,l,m,n,o=r.ajaxSetup({},c),p=o.context||o,q=o.context&&(p.nodeType||p.jquery)?r(p):r.event,s=r.Deferred(),t=r.Callbacks("once memory"),u=o.statusCode||{},v={},w={},x="canceled",y={readyState:0,getResponseHeader:function(a){var b;if(k){if(!h){h={};while(b=Eb.exec(g))h[b[1].toLowerCase()]=b[2]}b=h[a.toLowerCase()]}return null==b?null:b},getAllResponseHeaders:function(){return k?g:null},setRequestHeader:function(a,b){return null==k&&(a=w[a.toLowerCase()]=w[a.toLowerCase()]||a,v[a]=b),this},overrideMimeType:function(a){return null==k&&(o.mimeType=a),this},statusCode:function(a){var b;if(a)if(k)y.always(a[y.status]);else for(b in a)u[b]=[u[b],a[b]];return this},abort:function(a){var b=a||x;return e&&e.abort(b),A(0,b),this}};if(s.promise(y),o.url=((b||o.url||tb.href)+"").replace(Hb,tb.protocol+"//"),o.type=c.method||c.type||o.method||o.type,o.dataTypes=(o.dataType||"*").toLowerCase().match(L)||[""],null==o.crossDomain){j=d.createElement("a");try{j.href=o.url,j.href=j.href,o.crossDomain=Lb.protocol+"//"+Lb.host!=j.protocol+"//"+j.host}catch(z){o.crossDomain=!0}}if(o.data&&o.processData&&"string"!=typeof o.data&&(o.data=r.param(o.data,o.traditional)),Nb(Ib,o,c,y),k)return y;l=r.event&&o.global,l&&0===r.active++&&r.event.trigger("ajaxStart"),o.type=o.type.toUpperCase(),o.hasContent=!Gb.test(o.type),f=o.url.replace(Cb,""),o.hasContent?o.data&&o.processData&&0===(o.contentType||"").indexOf("application/x-www-form-urlencoded")&&(o.data=o.data.replace(Bb,"+")):(n=o.url.slice(f.length),o.data&&(f+=(vb.test(f)?"&":"?")+o.data,delete o.data),o.cache===!1&&(f=f.replace(Db,"$1"),n=(vb.test(f)?"&":"?")+"_="+ub++ +n),o.url=f+n),o.ifModified&&(r.lastModified[f]&&y.setRequestHeader("If-Modified-Since",r.lastModified[f]),r.etag[f]&&y.setRequestHeader("If-None-Match",r.etag[f])),(o.data&&o.hasContent&&o.contentType!==!1||c.contentType)&&y.setRequestHeader("Content-Type",o.contentType),y.setRequestHeader("Accept",o.dataTypes[0]&&o.accepts[o.dataTypes[0]]?o.accepts[o.dataTypes[0]]+("*"!==o.dataTypes[0]?", "+Kb+"; q=0.01":""):o.accepts["*"]);for(m in o.headers)y.setRequestHeader(m,o.headers[m]);if(o.beforeSend&&(o.beforeSend.call(p,y,o)===!1||k))return y.abort();if(x="abort",t.add(o.complete),y.done(o.success),y.fail(o.error),e=Nb(Jb,o,c,y)){if(y.readyState=1,l&&q.trigger("ajaxSend",[y,o]),k)return y;o.async&&o.timeout>0&&(i=a.setTimeout(function(){y.abort("timeout")},o.timeout));try{k=!1,e.send(v,A)}catch(z){if(k)throw z;A(-1,z)}}else A(-1,"No Transport");function A(b,c,d,h){var j,m,n,v,w,x=c;k||(k=!0,i&&a.clearTimeout(i),e=void 0,g=h||"",y.readyState=b>0?4:0,j=b>=200&&b<300||304===b,d&&(v=Pb(o,y,d)),v=Qb(o,v,y,j),j?(o.ifModified&&(w=y.getResponseHeader("Last-Modified"),w&&(r.lastModified[f]=w),w=y.getResponseHeader("etag"),w&&(r.etag[f]=w)),204===b||"HEAD"===o.type?x="nocontent":304===b?x="notmodified":(x=v.state,m=v.data,n=v.error,j=!n)):(n=x,!b&&x||(x="error",b<0&&(b=0))),y.status=b,y.statusText=(c||x)+"",j?s.resolveWith(p,[m,x,y]):s.rejectWith(p,[y,x,n]),y.statusCode(u),u=void 0,l&&q.trigger(j?"ajaxSuccess":"ajaxError",[y,o,j?m:n]),t.fireWith(p,[y,x]),l&&(q.trigger("ajaxComplete",[y,o]),--r.active||r.event.trigger("ajaxStop")))}return y},getJSON:function(a,b,c){return r.get(a,b,c,"json")},getScript:function(a,b){return r.get(a,void 0,b,"script")}}),r.each(["get","post"],function(a,b){r[b]=function(a,c,d,e){return r.isFunction(c)&&(e=e||d,d=c,c=void 0),r.ajax(r.extend({url:a,type:b,dataType:e,data:c,success:d},r.isPlainObject(a)&&a))}}),r._evalUrl=function(a){return r.ajax({url:a,type:"GET",dataType:"script",cache:!0,async:!1,global:!1,"throws":!0})},r.fn.extend({wrapAll:function(a){var b;return this[0]&&(r.isFunction(a)&&(a=a.call(this[0])),b=r(a,this[0].ownerDocument).eq(0).clone(!0),this[0].parentNode&&b.insertBefore(this[0]),b.map(function(){var a=this;while(a.firstElementChild)a=a.firstElementChild;return a}).append(this)),this},wrapInner:function(a){return r.isFunction(a)?this.each(function(b){r(this).wrapInner(a.call(this,b))}):this.each(function(){var b=r(this),c=b.contents();c.length?c.wrapAll(a):b.append(a)})},wrap:function(a){var b=r.isFunction(a);return this.each(function(c){r(this).wrapAll(b?a.call(this,c):a)})},unwrap:function(a){return this.parent(a).not("body").each(function(){r(this).replaceWith(this.childNodes)}),this}}),r.expr.pseudos.hidden=function(a){return!r.expr.pseudos.visible(a)},r.expr.pseudos.visible=function(a){return!!(a.offsetWidth||a.offsetHeight||a.getClientRects().length)},r.ajaxSettings.xhr=function(){try{return new a.XMLHttpRequest}catch(b){}};var Rb={0:200,1223:204},Sb=r.ajaxSettings.xhr();o.cors=!!Sb&&"withCredentials"in Sb,o.ajax=Sb=!!Sb,r.ajaxTransport(function(b){var c,d;if(o.cors||Sb&&!b.crossDomain)return{send:function(e,f){var g,h=b.xhr();if(h.open(b.type,b.url,b.async,b.username,b.password),b.xhrFields)for(g in b.xhrFields)h[g]=b.xhrFields[g];b.mimeType&&h.overrideMimeType&&h.overrideMimeType(b.mimeType),b.crossDomain||e["X-Requested-With"]||(e["X-Requested-With"]="XMLHttpRequest");for(g in e)h.setRequestHeader(g,e[g]);c=function(a){return function(){c&&(c=d=h.onload=h.onerror=h.onabort=h.onreadystatechange=null,"abort"===a?h.abort():"error"===a?"number"!=typeof h.status?f(0,"error"):f(h.status,h.statusText):f(Rb[h.status]||h.status,h.statusText,"text"!==(h.responseType||"text")||"string"!=typeof h.responseText?{binary:h.response}:{text:h.responseText},h.getAllResponseHeaders()))}},h.onload=c(),d=h.onerror=c("error"),void 0!==h.onabort?h.onabort=d:h.onreadystatechange=function(){4===h.readyState&&a.setTimeout(function(){c&&d()})},c=c("abort");try{h.send(b.hasContent&&b.data||null)}catch(i){if(c)throw i}},abort:function(){c&&c()}}}),r.ajaxPrefilter(function(a){a.crossDomain&&(a.contents.script=!1)}),r.ajaxSetup({accepts:{script:"text/javascript, application/javascript, application/ecmascript, application/x-ecmascript"},contents:{script:/\b(?:java|ecma)script\b/},converters:{"text script":function(a){return r.globalEval(a),a}}}),r.ajaxPrefilter("script",function(a){void 0===a.cache&&(a.cache=!1),a.crossDomain&&(a.type="GET")}),r.ajaxTransport("script",function(a){if(a.crossDomain){var b,c;return{send:function(e,f){b=r("